JeVois  1.18
JeVois Smart Embedded Machine Vision Toolkit
Share this page:
Engine.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 
22 #include <jevois/Types/Enum.H>
23 #include <jevois/Image/RawImage.H>
25 #include <jevois/Debug/Watchdog.H>
26 
27 #include <memory>
28 #include <mutex>
29 #include <vector>
30 #include <list>
31 #include <atomic>
32 
33 // #################### Platform mode config:
34 #ifdef JEVOIS_PLATFORM
35 
36 #if defined(JEVOIS_A33)
37 // ########## JeVois-A33 platform:
38 
39 // On the JeVois-A33 platform, we use a gadget driver by default to send output frames over USB, one hardware serial
40 // driver, and one serial-over-USB driver:
41 
42 //! On platform hardware, device for the camera sensor
43 #define JEVOIS_CAMERA_DEFAULT "/dev/video0"
44 
45 //! On platform hardware, device for the USB gadget driver (which sends video frames over USB to a host computer)
46 #define JEVOIS_GADGET_DEFAULT "/dev/video1"
47 
48 //! On platform hardware, device for the 4-pin hardware serial port
49 #define JEVOIS_SERIAL_DEFAULT "/dev/ttyS0"
50 
51 //! On platform hardware, device for serial-over-USB port
52 #define JEVOIS_USBSERIAL_DEFAULT "/dev/ttyGS0"
53 
54 //! Default camera sensor
55 #define JEVOIS_CAMERASENS_DEFAULT CameraSensor::ov9650
56 
57 //! Default IMU spi device
58 #define JEVOIS_IMUSPI_DEFAULT ""
59 
60 #elif defined(JEVOIS_PRO)
61 // ########## JeVois-Pro platform:
62 
63 // On the JeVois-Pro platform, we have no gadget for now (which will trigger displaying output frames to a window), one
64 // hardware serial driver, and not yet one serial-over-USB driver:
65 
66 //! On platform hardware, device for the camera sensor
67 #define JEVOIS_CAMERA_DEFAULT "/dev/video0"
68 
69 //! On platform hardware, device for the USB gadget driver (which sends video frames over USB to a host computer)
70 #define JEVOIS_GADGET_DEFAULT ""
71 
72 //! On platform hardware, device for the 4-pin hardware serial port
73 #define JEVOIS_SERIAL_DEFAULT "/dev/ttyS4"
74 
75 //! On platform hardware, device for serial-over-USB port
76 #define JEVOIS_USBSERIAL_DEFAULT ""
77 //#define JEVOIS_USBSERIAL_DEFAULT "/dev/ttyGS0"
78 
79 //! Default camera sensor
80 #define JEVOIS_CAMERASENS_DEFAULT CameraSensor::imx290
81 
82 //! Default IMU spi device
83 #define JEVOIS_IMUSPI_DEFAULT "/dev/spidev32766.0"
84 
85 #else
86 #error "Neither JEVOIS_A33 nor JEVOIS_PRO defined -- ABORT"
87 #endif
88 
89 #else // JEVOIS_PLATFORM
90 // #################### Host mode config:
91 
92 // On the host, we have no gadget (which will trigger displaying output frames to a window) and we use the terminal in
93 // which jevois-daemon was started for serial commands:
94 
95 //! On generic computer hardware, device for the camera sensor
96 #define JEVOIS_CAMERA_DEFAULT "/dev/video0"
97 
98 //! On generic computer hardware, device for the USB gadget driver should always be empty
99 #define JEVOIS_GADGET_DEFAULT ""
100 
101 //! On generic computer hardware, device for serial port should always be stdio to use an StdioInterface
102 #define JEVOIS_SERIAL_DEFAULT "stdio"
103 
104 //! On generic computer hardware, device for the serial-over-USB port should always be empty
105 #define JEVOIS_USBSERIAL_DEFAULT ""
106 
107 //! Default IMU spi device
108 #define JEVOIS_IMUSPI_DEFAULT ""
109 
110 #ifdef JEVOIS_PRO
111 //! Default camera sensor
112 #define JEVOIS_CAMERASENS_DEFAULT CameraSensor::imx290
113 #else
114 //! Default camera sensor
115 #define JEVOIS_CAMERASENS_DEFAULT CameraSensor::ov9650
116 #endif
117 
118 #endif // JEVOIS_PLATFORM
119 
120 namespace jevois
121 {
122  class VideoInput;
123  class VideoOutput;
124  class Module;
125  class DynamicLoader;
126  class UserInterface;
127  class GUIhelper;
128  class GUIconsole;
129  class Camera;
130  class IMU;
131 
132  namespace engine
133  {
134  static ParameterCategory const ParamCateg("Engine Options");
135 
136  //! Parameter \relates jevois::Engine
137  JEVOIS_DECLARE_PARAMETER(cameradev, std::string, "Camera device name (if starting with /dev/v...), or movie "
138  "file name (e.g., movie.mpg) or image sequence (e.g., im%02d.jpg, to read frames "
139  "im00.jpg, im01.jpg, etc).",
140  JEVOIS_CAMERA_DEFAULT, ParamCateg);
141 
142  //! Parameter \relates jevois::Engine
143  JEVOIS_DECLARE_PARAMETER(camerasens, CameraSensor, "Camera sensor. Users would usually not set this parameter "
144  "manually, it is set through boot-time configuration.",
145  JEVOIS_CAMERASENS_DEFAULT, CameraSensor_Values, ParamCateg);
146 
147  JEVOIS_DECLARE_PARAMETER(imudev, std::string, "IMU SPI device name, typically starting with /dev/spidev..., "
148  "or empty if device does not have an IMU with SPI interface.",
149  JEVOIS_IMUSPI_DEFAULT, ParamCateg);
150 
151  //! Parameter \relates jevois::Engine
152  JEVOIS_DECLARE_PARAMETER(cameranbuf, unsigned int, "Number of video input (camera) buffers, or 0 for automatic.",
153  0, ParamCateg);
154 
155  //! Parameter \relates jevois::Engine
156  JEVOIS_DECLARE_PARAMETER(gadgetdev, std::string, "Gadget device name. This is used on platform hardware only. "
157  "On host hardware, a display window will be used unless gadgetdev is None (useful "
158  "for benchmarking) or is a file stem for a movie file that does not start with /dev/ "
159  "(and which should contain a printf-style directive for a single int argument, "
160  "the movie number).",
161  JEVOIS_GADGET_DEFAULT, ParamCateg);
162 
163  //! Parameter \relates jevois::Engine
164  JEVOIS_DECLARE_PARAMETER(gadgetnbuf, unsigned int, "Number of video output (USB video) buffers, or 0 for auto",
165  0, ParamCateg);
166 
167  //! Parameter \relates jevois::Engine
168  JEVOIS_DECLARE_PARAMETER(videomapping, int, "Index of Video Mapping to use, or -1 to use the default mapping. "
169  "Note that this parameter is only available when parsing command-line arguments. "
170  "At runtime, the setmapping command should be used instead.",
171  -1, ParamCateg);
172 
173  //! Parameter \relates jevois::Engine
174  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(serialdev, std::string, "Hardware (4-pin connector) serial device name, "
175  "or 'stdio' to use the console, or empty for no hardware serial port",
176  JEVOIS_SERIAL_DEFAULT, ParamCateg);
177 
178  //! Parameter \relates jevois::Engine
179  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(usbserialdev, std::string, "Over-the-USB serial device name, or empty",
180  JEVOIS_USBSERIAL_DEFAULT, ParamCateg);
181 
182  //! Parameter \relates jevois::Engine
183  JEVOIS_DECLARE_PARAMETER(camreg, bool, "Enable raw access to camera registers through setcamreg and getcamreg",
184  false, ParamCateg);
185 
186  //! Parameter \relates jevois::Engine
187  JEVOIS_DECLARE_PARAMETER(imureg, bool, "Enable raw access to IMU registers through setimureg and getimureg",
188  false, ParamCateg);
189 
190  //! Parameter \relates jevois::Engine
191  JEVOIS_DECLARE_PARAMETER(camturbo, bool, "Enable camera turbo mode by relaxing the need for DMA-coherent video "
192  "buffer memory. This can accelerate severalfolds access to the captured image data, but "
193  "it may also yield stripe artifacts with some modules, such as PassThrough. The stripes "
194  "are pieces of incorrect data in the cache. You should experiment with each particular "
195  "module. Turbo mode is not recommended for any production-grade application.",
196  false, ParamCateg);
197 
198  //! Enum for Parameter \relates jevois::Engine
199  JEVOIS_DEFINE_ENUM_CLASS(SerPort, (None) (All) (Hard) (USB) );
200 
201  //! Parameter \relates jevois::Engine
202  JEVOIS_DECLARE_PARAMETER(serlog, SerPort, "Show log and debug messages on selected serial port(s)",
203  SerPort::None, SerPort_Values, ParamCateg);
204 
205  //! Parameter \relates jevois::Engine
206  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(videoerrors, bool, "Show any machine vision module errors (exceptions) "
207  "in the video stream. Only takes effect if streaming video to USB.",
208  true, ParamCateg);
209 
210  //! Parameter \relates jevois::Engine
211  JEVOIS_DECLARE_PARAMETER(serout, SerPort, "Send module serial messages to selected serial port(s)",
212  SerPort::None, SerPort_Values, ParamCateg);
213 
214  //! Enum for Parameter \relates jevois::Engine
215  JEVOIS_DEFINE_ENUM_CLASS(CPUmode, (PowerSave) (Conservative) (OnDemand) (Interactive) (Performance) );
216 
217  //! Parameter \relates jevois::Engine
218  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(cpumode, CPUmode, "CPU frequency modulation mode"
219 #ifdef JEVOIS_PRO
220  " for A73 big cores"
221 #endif
222  , CPUmode::Performance, CPUmode_Values, ParamCateg);
223 
224 #ifdef JEVOIS_PRO
225  //! Parameter \relates jevois::Engine
226  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(cpumodel, CPUmode, "CPU frequency modulation mode for A53 little cores",
227  CPUmode::Performance, CPUmode_Values, ParamCateg);
228 #endif
229 
230  //! Parameter \relates jevois::Engine
231  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(cpumax, unsigned int, "CPU maximum frequency in MHz"
232 #ifdef JEVOIS_PRO
233  ". To enable overclock frequencies above 2208 MHz, you need to first edit "
234  "/boot/env.txt and change max_freq_a73, then reboot. Use with caution!"
235 #endif
236 #ifdef JEVOIS_A33
237  // keep this in sync with sunxi-cpufreq.c
238  , 1344, { 120, 240, 312, 408, 480, 504, 600, 648, 720, 816, 912, 1008,
239  1044, 1056, 1080, 1104, 1116, 1152, 1200, 1224, 1248, 1296, 1344 },
240 #else
241  // keep this in sync with device tree
242  // A73 cores
243  , 2208, { 500, 667, 1000, 1200, 1398, 1512, 1608, 1704, 1800, 1908, 2016,
244  2100, 2208, 2304, 2400 },
245  // A53 cores
246  //1800, { 500, 667, 1000, 1200, 1398, 1512, 1608, 1704, 1800, 1908, 2016,
247  // 2100, 2208 },
248 #endif
249  ParamCateg);
250 #ifdef JEVOIS_PRO
251  //! Parameter \relates jevois::Engine
252  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(cpumaxl, unsigned int, "CPU maximum frequency in MHz, for A53 little cores. "
253  "To enable overclock frequencies above 1800 MHz, you need to first edit "
254  "/boot/env.txt and change max_freq_a53, then reboot. Use with caution!",
255  // keep this in sync with device tree
256  1800, { 500, 667, 1000, 1200, 1398, 1512, 1608, 1704, 1800, 1908, 2016,
257  2100, 2208 },
258  ParamCateg);
259 #endif
260 
261  //! Parameter \relates jevois::Engine
262  JEVOIS_DECLARE_PARAMETER(multicam, bool, "Allow up to 3 JeVois cameras on one USB bus. Enabling this "
263  "reduces the amount of USB bandwidth used by each JeVois camera, from 3kb "
264  "per USB isochronous microframe to 1kb. All 3 JeVois cameras must have this "
265  "option enabled, and the JeVois linux kernel module should also have "
266  "been loaded with multicam on.",
267  false, ParamCateg);
268 
269  //! Parameter \relates jevois::Engine
270  JEVOIS_DECLARE_PARAMETER(quietcmd, bool, "When true, do not issue a message 'OK' after every correct command "
271  "received at the command-line interface. Recommended for advanced users only.",
272  false, ParamCateg);
273 
274  //! Parameter \relates jevois::Engine
275  JEVOIS_DECLARE_PARAMETER(python, bool, "When true, enable support for modules written in Python. Otherwise, "
276  "attempting to load a python module will throw an exception. Disabling python saves "
277  "a lot of memory and may be useful when using C++ modules that run large deep neural "
278  "networks.",
279  true, ParamCateg);
280 
281  //! Parameter \relates jevois::Engine
282  JEVOIS_DECLARE_PARAMETER(serlimit, size_t, "Maximum number of serial messages that can be sent by a module "
283  "using sendSerial(), for each video frame, or 0 for no limit. Any message sent by "
284  "the module beyond the first serlimit ones will be dropped. This is useful to avoid "
285  "overloading the serial link, for example in case one is running a ArUco detector and "
286  "a large number of ArUco tags are present in the field of view of JeVois.",
287  0, ParamCateg);
288 
289 #ifdef JEVOIS_PRO
290  //! Parameter \relates jevois::Engine
291  JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(gui, bool, "Use a graphical user interface instead of plain display "
292  "when true",
293  true, ParamCateg);
294  //! Parameter \relates jevois::Engine
295  JEVOIS_DECLARE_PARAMETER(conslock, bool, "Lock the console and capture the keyboard and mouse to avoid "
296  "interference, only effective on JeVois-Pro Platform, otherwise ignored. Set conslock "
297  "to false if you are experiencing hard crashes and want to run jevoispro-daemon in gdb.",
298  true, ParamCateg);
299 
300  //! Parameter \relates jevois::Engine
301  JEVOIS_DECLARE_PARAMETER(watchdog, double, "Timeout in seconds after which we kill this process if the main loop "
302  "is stuck somehow, or 0.0 for no watchdog",
303  10.0, ParamCateg);
304 #endif
305  }
306 
307  //! JeVois processing engine - gets images from camera sensor, processes them, and sends results over USB
308  /*! The Engine is orchestrating the execution of vision processing software. It is a Manager, i.e., it is the root of
309  a hierarchy of Component objects and it handles access to their Parameter settings and their construction, init(),
310  unInit(), and destruction. The component hierarchy consists of Engine at the root, then one Module which is
311  selected by the user at runtime, e.g., by selecting a given video format on video camera software running on a
312  host computer connected to the JeVois hardware. The Module may then contain an arbitrarily complex hierarchy of
313  Component objects with Parameter settings in them. Module derives from Component and thus may also have its own
314  Parameter settings.
315 
316  Engine contains the following basic elements:
317 
318  - A VideoInput, instantiated as either a Camera for live video streaming or a MovieInput for processing of
319  pre-recorded video files or sequences of images (useful during algorithm development, to test and optimize on
320  reproducible inputs);
321 
322  - A VideoOutput, instantiated either as a USB Gadget driver when running on the JeVois hardware platform, or as a
323  VideoDisplay when running on a computer that has a graphics display, or as a MovieOutput to save output video
324  frames to disk, or as a VideoOutputNone if desired for benchmarking of vision algorithms while discounting any
325  work related to transmitting output frames.
326 
327  - A DynamicLoader which handles loading the chosen vision processing Module at runtime depending on user
328  selections;
329 
330  - Any number of UserInterface objects, instantiated as either a hardware Serial port (for the 4-pin JST 1.0mm
331  connector on the platform hardware), a serial-over-USB Serial port (visible on the host computer to which the
332  JeVois hardware is connected by USB), or an StdioInterface (used to accept commands and print results directly
333  in the terminal where the JeVois Engine was started, particularly useful when running on a generic computer as
334  opposed to the platform hardware). When running on platform hardware, usually two UserInterface objects are
335  created (one hardware Serial, one serial-over-USB Serial), while, when running on a generic computer, usually
336  only one UserInterface is created (of type StdioInterface to accept commands directly in the terminal in which
337  the jevois-daemon was started);
338 
339  - The list of VideoMapping definitions imported from your videomappings.cfg file. These definitions specify which
340  video output modes are available over USB and their corresponding Camera settings and which Module to use, as
341  well as which modes are available that do not have any sreaming video output over USB (e.g., when connecting the
342  hardware platform to an Arduino only).
343 
344  The main loop of Engine runs until the user decides to quit, and basically goes through the following steps:
345 
346  - Create an InputFrame object which is an exception-safe wrapper around the next available Camera frame. The frame
347  may not have been captured yet. The InputFrame can be understood as a mechanism to gain access to that frame in
348  the future, when it has become available (i.e., has been captured by the camera). This is very similar to the
349  std::future framework of C++11.
350 
351  - When the current VideoMapping specifies that we will be streaming video frames out over USB, also create an
352  OutputFrame object which is an exception-safe wrapper around the next available Gadget frame. This is also just
353  a mechanism for gaining access to the next blank video buffer that is available from the USB driver and that we
354  should fill with interesting pixel data before sending it over USB to a host computer.
355 
356  - Call the currently-loaded Module's process() function, either as process(InputFrame, OutputFrame) when the
357  current VideoMapping specifies that some video output is to be sent over USB, or as process(InputFrame) when the
358  current VideoMapping specifies no video output. Any exception thrown by the Module's process() function will be
359  caught, reported, and ignored. The process() function would typically request the next available camera image
360  through the InputFrame wrapper (this request may block until the frame has been captured by the camera sensor
361  hardware), process that image, request the next available output image through the OutputFrame wrapper (when
362  VideoMapping specifies that there is USB video output), and paint some results into that output image, which
363  will then be sent to the host coputer over USB, for display by some webcam program or for further processing by
364  some custom vision software running on that computer. In addition, the currently loaded Module may issue
365  messages over the UserInterface ports (e.g., indicating the location at which an object was found, to let an
366  Arduino know about it).
367 
368  - Read any new commands issued by users over the UserInterface ports and execute the appropriate commands.
369 
370  - Handle user requests to change VideoMapping, when they select a different video mode in their webcam software
371  running on the host computer connected to the JeVois hardware. Such requests may trigger unloading of the
372  current Module and loading a new one, and changing camera pixel format, image size, etc. These changes are
373  guaranteed to occur when the Module's process() function is not running, i.e., Module programmers do not have to
374  worry about possible changes in image dimensions or pixel formats during execution of their process() function.
375 
376  - Pass any user requests received over USB or UserInterface to adjust camera parameters to the actual Camera
377  hardware driver (e.g., when users change contrast in their webcam program, that request is sent to the Engine
378  over USB, and the Engine then forwards it to the Camera hardware driver).
379 
380  \ingroup core */
381  class Engine : public Manager,
382  public Parameter<engine::cameradev, engine::camerasens, engine::cameranbuf, engine::gadgetdev,
383  engine::gadgetnbuf, engine::imudev, engine::videomapping, engine::serialdev,
384  engine::usbserialdev, engine::camreg, engine::imureg, engine::camturbo,
385  engine::serlog, engine::videoerrors, engine::serout, engine::cpumode, engine::cpumax,
386  engine::multicam, engine::quietcmd, engine::python, engine::serlimit
387 #ifdef JEVOIS_PRO
388  , engine::gui, engine::conslock, engine::cpumaxl, engine::cpumodel, engine::watchdog
389 #endif
390  >
391  {
392  public:
393  //! Constructor
394  Engine(std::string const & instance);
395 
396  //! Constructor with command-line parsing
397  Engine(int argc, char const* argv[], std::string const & instance);
398 
399  //! Destructor
400  ~Engine();
401 
402  //! Re-load video mappings from videomappings.cfg
403  /*! Mappings are automatically loaded on startup so this should only be used if the file has been modified and the
404  mappings need to be refreshed. Note that this will not refresh the available resolutions for USB output, which
405  requires a full reboot to re-initialize the kernel Gadget module. Also beware of possible state inconsistency
406  (e.g., if external code is holding a reference previously returned by findVideoMapping(). So, use with
407  caution. Basically, only GUIhelper should use this. */
408  void reloadVideoMappings();
409 
410  //! Find the VideoMapping that has the given output specs, or throw if not found
411  VideoMapping const & findVideoMapping(unsigned int oformat, unsigned int owidth, unsigned int oheight,
412  float oframespersec) const;
413 
414  //! Get the current video mapping
415  /*! Note that the current mapping may not have an entry in our list of mappings obtained from videomappings.cfg,
416  if the current one was set on the fly by the setmapping2 CLI command. */
417  VideoMapping const & getCurrentVideoMapping() const;
418 
419  //! Return the number of video mappings
420  size_t numVideoMappings() const;
421 
422  //! Allow access to our video mappings which are parsed from file at construction
423  VideoMapping const & getVideoMapping(size_t idx) const;
424 
425  //! Get the video mapping index for a given UVC iformat, iframe and interval
426  size_t getVideoMappingIdx(unsigned int iformat, unsigned int iframe, unsigned int interval) const;
427 
428  //! Allow access to the default video mapping
429  VideoMapping const & getDefaultVideoMapping() const;
430 
431  //! Allow access to the default video mapping index
432  size_t getDefaultVideoMappingIdx() const;
433 
434  //! Run a function on every video mapping
435  /*! The first mapping your function will be called on is for mapping with index 0, and so on until index
436  numVideoMappings()-1. If your function throws, we report the exception and then ignore it, then we move on to
437  the next mapping. */
438  void foreachVideoMapping(std::function<void(VideoMapping const & m)> && func);
439 
440  //! Use this to request a format change from within process()
441  /*! This should only be used on JeVois-Pro in GUI mode. The engine is locked up hence and setFormat() cannot be
442  called from within a Module's process function, to avoid possible disasters of changing format while we
443  process. Modules or the GUI can use requestSetFormat() to request a format change in between two calls to
444  process(). Note special values: -1 to just reload the current format (e.g., after editing code), -2 does
445  nothing. */
446  void requestSetFormat(int idx);
447 
448  //! Terminate the program
449  void quit();
450 
451  //! Request a reboot
452  /*! On JeVois-A33 Platform, trigger a hard reset. On JeVois-Pro Platform or JeVois-Host, just terminate the
453  program. */
454  void reboot();
455 
456  //! Callback for when the user selects a new output video format
457  /*! Here, we stop streaming, nuke any current processing module, set the camera format, set the gadget output
458  format, load the new processing module, and start streaming again. The given VideoMapping will typically be
459  obtained using findVideoMapping() from output specs received over the USB link. */
460  void setFormat(size_t idx);
461 
462  //! Start streaming on video from camera, processing, and USB
463  void streamOn();
464 
465  //! Stop streaming on video from camera, processing, and USB
466  void streamOff();
467 
468  //! Main loop: grab, process, send over USB. Should be called by main application thread
469  int mainLoop();
470 
471  //! Send a string to all serial ports
472  /*! \note When islog is true, this is assumes to be a log message, and it will be sent to the port(s) specified by
473  parameter serlog. Otherwise, the message will be sent to the ports specified by parameter serout. Note how the
474  number of messages that can be sent for each video frame may be limited by parameter \p serlimit; only up to
475  \p serlimit messages will be sent for a given video frame. This is useful to avoid overloading the serial
476  link, for example in cases one is running a ArUco detector and a large number of ArUco tags are present in the
477  field of view of JeVois. */
478  void sendSerial(std::string const & str, bool islog = false);
479 
480  //! Get a pointer to our current module (may be null)
481  std::shared_ptr<Module> module() const;
482 
483  //! Get a pointer to our IMU (may be null)
484  std::shared_ptr<IMU> imu() const;
485 
486  //! Get a pointer to our Camera (may be null, especially if not using a camera but, eg, movie input)
487  std::shared_ptr<Camera> camera() const;
488 
489 #ifdef JEVOIS_PRO
490  //! Draw all camera controls into our GUI
491  void drawCameraGUI();
492 #endif
493 
494  //! Register a component as linked to some python code, used by dynamic params created in python
495  /*! Use with extreme caution to guarantee thread safety and object lifetime since we just use raw pointers here */
496  void registerPythonComponent(Component * comp, void * pyinst);
497 
498  //! Unregister a component as linked to some python code, used by dynamic params created in python
499  /*! Use with extreme caution to guarantee thread safety and object lifetime since we just use raw pointers here */
501 
502  //! Get the component registered with a given python instance
503  /*! Use with extreme caution to guarantee thread safety and object lifetime since we just use raw pointers here */
504  Component * getPythonComponent(void * pyinst) const;
505 
506  // Report an error to console and JeVois-Pro GUI
507  /*! Try to minimize the use of this function, and normally use LERROR() or LFATAL() instead. Currently the only
508  use is in jevois::dnn::Pipeline, to report parameters set in the zoo file but not used by the pipeline, as
509  issuing an LFATAL() for that may be too strict, but issuing an LERROR() may go un-noticed since the pipeline
510  is still running just fine. */
511  void reportError(std::string const & err);
512 
513  //! Clear all errors currently displayed in the JeVois-Pro GUI
514  /*! In the JevoisPro GUI, errors reported via reportError() remain displayed for a few seconds, but sometimes we
515  want to clear them right away, e.g., after DNN pipeline threw, if the user selects another one, we want the
516  previous error to disappear immediately since it is not applicable anymore. When the JeVois-Pro GUI is not
517  used, this has no effect. */
518  void clearErrors();
519 
520  protected:
521  //! Run a script from file
522  /*! The filename should be absolute. The file should have any of the commands supported by Engine, one per
523  line. Filename should be relative to the current module's path. */
524  void runScriptFromFile(std::string const & filename, std::shared_ptr<UserInterface> ser,
525  bool throw_no_file);
526 
527  //! Parameter callback
528  void onParamChange(engine::serialdev const & param, std::string const & newval) override;
529 
530  //! Parameter callback
531  void onParamChange(engine::usbserialdev const & param, std::string const & newval) override;
532 
533  //! Parameter callback
534  void onParamChange(engine::cpumode const & param, engine::CPUmode const & newval) override;
535 
536  //! Parameter callback
537  void onParamChange(engine::cpumax const & param, unsigned int const & newval) override;
538 
539  //! Parameter callback
540  void onParamChange(engine::videoerrors const & param, bool const & newval) override;
541 
542 #ifdef JEVOIS_PRO
543  //! Parameter callback
544  void onParamChange(engine::gui const & param, bool const & newval) override;
545 
546  //! Parameter callback
547  void onParamChange(engine::cpumaxl const & param, unsigned int const & newval) override;
548 
549  //! Parameter callback
550  void onParamChange(engine::cpumodel const & param, engine::CPUmode const & newval) override;
551 #endif
552 
553  size_t itsDefaultMappingIdx; //!< Index of default mapping
554  std::vector<VideoMapping> itsMappings; //!< All our mappings from videomappings.cfg
555  VideoMapping itsCurrentMapping { }; //!< Current mapping, may not match any in itsMappings if setmapping2 used
556 
557  std::shared_ptr<VideoInput> itsCamera; //!< Our camera
558  std::shared_ptr<IMU> itsIMU; //! Our IMU
559  std::shared_ptr<VideoOutput> itsGadget; //!< Our gadget
560 
561  std::unique_ptr<DynamicLoader> itsLoader; //!< Our module loader
562  std::shared_ptr<Module> itsModule; //!< Our current module
563 
564  std::atomic<bool> itsRunning; //!< True when we are running
565  std::atomic<bool> itsStreaming; //!< True when we are streaming video
566  std::atomic<bool> itsStopMainLoop; //!< Flag used to stop the main loop
567 
568  mutable std::timed_mutex itsMtx; //!< Mutex to protect our internals
569 
570  void preInit() override; //!< Override of Manager::preInit()
571  void postInit() override; //!< Override of Manager::postInit()
572 
573  //! Parse a user command received over serial port
574  /*! Throw upon receiving an incorrect command (eg, bad parameter value), return true if success, return false if
575  command was not recognized and should be tried by Module. pfx is an optional prefix which will be added to all
576  produced messages or errors. */
577  bool parseCommand(std::string const & str, std::shared_ptr<UserInterface> s, std::string const & pfx = "");
578 
579  private:
580  std::list<std::shared_ptr<UserInterface> > itsSerials;
581 
582  void setFormatInternal(size_t idx); // itsMtx should be locked by caller
583  void setFormatInternal(jevois::VideoMapping const & m, bool reload = false); // itsMtx should be locked by caller
584 
585  // Loop over all available camera controls and run a function on each:
586  void foreachCamCtrl(std::function<void(struct v4l2_queryctrl & qc, std::set<int> & doneids)> && func);
587 
588  // Return help string for a camera control or throw
589  std::string camCtrlHelp(struct v4l2_queryctrl & qc, std::set<int> & doneids);
590 
591  // Return machine-oriented string for a camera control or throw
592  std::string camCtrlInfo(struct v4l2_queryctrl & qc, std::set<int> & doneids);
593 
594  // Send info about built-in engine commands
595  void cmdInfo(std::shared_ptr<UserInterface> s, bool showAll, std::string const & pfx = "");
596 
597  // Send info about module commands
598  void modCmdInfo(std::shared_ptr<UserInterface> s, std::string const & pfx = "");
599 
600  // Get short name from V4L2 ID, long name is a backup in case we don't find the control in our list
601  std::string camctrlname(int id, char const * longname) const;
602 
603  // Get V4L2 ID from short name
604  int camctrlid(std::string const & shortname);
605 
606  // Report an error to console, video frame, or GUI
607  /*! Call this from within catch. Note, in GUI mode, this calls endFrame() so it should not be used except for
608  exceptions that will not be ignored. */
609  void reportErrorInternal(std::string const & err = "");
610 
611  bool itsShellMode; // When true, pass any CLI command to the Linux shell
612  bool itsTurbo;
613  bool itsManualStreamon; // allow manual streamon when outputing video to None or file
614  std::atomic<bool> itsVideoErrors; // fast cached value for engine::videoerrors
615  jevois::RawImage itsVideoErrorImage;
616  std::string itsModuleConstructionError; // Non-empty error message if module constructor threw
617 
618 #ifdef JEVOIS_PLATFORM_A33
619  // Things related to mass storage gadget to export our /jevois partition as a virtual USB flash drive:
620  void checkMassStorage(); // thread to check mass storage gadget status
621  std::future<void> itsCheckMassStorageFut;
622  std::atomic<bool> itsCheckingMassStorage;
623  std::atomic<bool> itsMassStorageMode;
624  void startMassStorageMode();
625  void stopMassStorageMode();
626 #endif
627 
628  std::atomic<size_t> itsNumSerialSent; // Number of serial messages sent this frame; see serlimit
629  std::atomic<int> itsRequestedFormat; // Set by requestSetFormat(), could be -1 to reload, otherwise -2
630 
631 #ifdef JEVOIS_PRO
632  std::shared_ptr<GUIhelper> itsGUIhelper;
633 
634  // Draw ImGui widgets for all camera controls
635  void camCtrlGUI(struct v4l2_queryctrl & qc, std::set<int> & doneids);
636 
637  std::shared_ptr<jevois::Watchdog> itsWatchdog;
638 #endif
639  // Python code registry, used to assign dynamic parameters created in python code to the correct owning component.
640  // This looks thread-unsafe but should be ok as long as objects inherit first from Component and then from
641  // PythonWrapper.
642  std::map<void *, Component *> itsPythonRegistry;
643  mutable std::mutex itsPyRegMtx;
644  };
645 } // namespace jevois
646 
jevois::Engine::getDefaultVideoMappingIdx
size_t getDefaultVideoMappingIdx() const
Allow access to the default video mapping index.
Definition: Engine.C:1308
JEVOIS_USBSERIAL_DEFAULT
#define JEVOIS_USBSERIAL_DEFAULT
On platform hardware, device for serial-over-USB port.
Definition: Engine.H:76
jevois::Engine::foreachVideoMapping
void foreachVideoMapping(std::function< void(VideoMapping const &m)> &&func)
Run a function on every video mapping.
Definition: Engine.C:1312
jevois::Engine::quit
void quit()
Terminate the program.
Definition: Engine.C:1603
jevois::Manager
Manager of a hierarchy of Component objects.
Definition: Manager.H:73
JEVOIS_CAMERA_DEFAULT
#define JEVOIS_CAMERA_DEFAULT
On platform hardware, device for the camera sensor.
Definition: Engine.H:67
Watchdog.H
jevois::Engine::itsModule
std::shared_ptr< Module > itsModule
Our current module.
Definition: Engine.H:562
Manager.H
RawImage.H
jevois::Component
A component of a model hierarchy.
Definition: Component.H:181
JEVOIS_GADGET_DEFAULT
#define JEVOIS_GADGET_DEFAULT
On platform hardware, device for the USB gadget driver (which sends video frames over USB to a host c...
Definition: Engine.H:70
jevois::Engine::itsRunning
std::atomic< bool > itsRunning
True when we are running.
Definition: Engine.H:564
jevois::Engine::camera
std::shared_ptr< Camera > camera() const
Get a pointer to our Camera (may be null, especially if not using a camera but, eg,...
Definition: Engine.C:1252
jevois::RawImage
A raw image as coming from a V4L2 Camera and/or being sent out to a USB Gadget.
Definition: RawImage.H:110
jevois::Engine::numVideoMappings
size_t numVideoMappings() const
Return the number of video mappings.
Definition: Engine.C:1260
jevois::Engine::unRegisterPythonComponent
void unRegisterPythonComponent(Component *comp)
Unregister a component as linked to some python code, used by dynamic params created in python.
Definition: Engine.C:2732
jevois::ParameterCategory
A category to which multiple ParameterDef definitions can belong.
Definition: ParameterDef.H:33
jevois::Engine::setFormat
void setFormat(size_t idx)
Callback for when the user selects a new output video format.
Definition: Engine.C:741
jevois::Engine::reboot
void reboot()
Request a reboot.
Definition: Engine.C:1582
jevois::Engine::itsCamera
std::shared_ptr< VideoInput > itsCamera
Our camera.
Definition: Engine.H:557
jevois::Engine::getDefaultVideoMapping
const VideoMapping & getDefaultVideoMapping() const
Allow access to the default video mapping.
Definition: Engine.C:1304
jevois::Engine::itsLoader
std::unique_ptr< DynamicLoader > itsLoader
Our module loader.
Definition: Engine.H:561
jevois
Definition: Concepts.dox:1
jevois::Engine::streamOn
void streamOn()
Start streaming on video from camera, processing, and USB.
Definition: Engine.C:702
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK(l2grad, bool, "Use more accurate L2 gradient norm if true, L1 if false", false, ParamCateg)
jevois::Engine::clearErrors
void clearErrors()
Clear all errors currently displayed in the JeVois-Pro GUI.
Definition: Engine.C:1186
jevois::JEVOIS_DEFINE_ENUM_CLASS
JEVOIS_DEFINE_ENUM_CLASS(CameraSensor,(any)(ov9650)(ov2640)(ov7725)(ar0135)(imx290)(os08a10))
Enum for different sensor models.
jevois::Engine::findVideoMapping
const VideoMapping & findVideoMapping(unsigned int oformat, unsigned int owidth, unsigned int oheight, float oframespersec) const
Find the VideoMapping that has the given output specs, or throw if not found.
Definition: Engine.C:1320
jevois::Engine::itsMtx
std::timed_mutex itsMtx
Mutex to protect our internals.
Definition: Engine.H:568
jevois::Component::Engine
friend class Engine
Definition: Component.H:518
jevois::engine::JEVOIS_DECLARE_PARAMETER
JEVOIS_DECLARE_PARAMETER(imudev, std::string, "IMU SPI device name, typically starting with /dev/spidev..., " "or empty if device does not have an IMU with SPI interface.", JEVOIS_IMUSPI_DEFAULT, ParamCateg)
jevois::Engine::streamOff
void streamOff()
Stop streaming on video from camera, processing, and USB.
Definition: Engine.C:713
jevois::Engine::requestSetFormat
void requestSetFormat(int idx)
Use this to request a format change from within process()
Definition: Engine.C:734
jevois::Engine
JeVois processing engine - gets images from camera sensor, processes them, and sends results over USB...
Definition: Engine.H:381
jevois::Engine::getVideoMapping
const VideoMapping & getVideoMapping(size_t idx) const
Allow access to our video mappings which are parsed from file at construction.
Definition: Engine.C:1264
jevois::Engine::runScriptFromFile
void runScriptFromFile(std::string const &filename, std::shared_ptr< UserInterface > ser, bool throw_no_file)
Run a script from file.
Definition: Engine.C:2507
jevois::Engine::reportError
void reportError(std::string const &err)
Definition: Engine.C:1177
VideoMapping.H
jevois::Engine::mainLoop
int mainLoop()
Main loop: grab, process, send over USB. Should be called by main application thread.
Definition: Engine.C:895
jevois::Engine::onParamChange
void onParamChange(engine::serialdev const &param, std::string const &newval) override
Parameter callback.
jevois::Engine::imu
std::shared_ptr< IMU > imu() const
Get a pointer to our IMU (may be null)
Definition: Engine.C:1248
jevois::Engine::itsIMU
std::shared_ptr< IMU > itsIMU
Definition: Engine.H:558
CameraSensor.H
jevois::Engine::itsMappings
std::vector< VideoMapping > itsMappings
All our mappings from videomappings.cfg.
Definition: Engine.H:554
jevois::Engine::getVideoMappingIdx
size_t getVideoMappingIdx(unsigned int iformat, unsigned int iframe, unsigned int interval) const
Get the video mapping index for a given UVC iformat, iframe and interval.
Definition: Engine.C:1273
jevois::Engine::itsDefaultMappingIdx
size_t itsDefaultMappingIdx
Index of default mapping.
Definition: Engine.H:553
jevois::Engine::preInit
void preInit() override
Override of Manager::preInit()
Definition: Engine.C:437
JEVOIS_CAMERASENS_DEFAULT
#define JEVOIS_CAMERASENS_DEFAULT
Default camera sensor.
Definition: Engine.H:80
jevois::Engine::itsStreaming
std::atomic< bool > itsStreaming
True when we are streaming video.
Definition: Engine.H:565
jevois::Engine::registerPythonComponent
void registerPythonComponent(Component *comp, void *pyinst)
Register a component as linked to some python code, used by dynamic params created in python.
Definition: Engine.C:2722
jevois::Engine::getPythonComponent
Component * getPythonComponent(void *pyinst) const
Get the component registered with a given python instance.
Definition: Engine.C:2741
jevois::Engine::postInit
void postInit() override
Override of Manager::postInit()
Definition: Engine.C:461
jevois::Engine::itsCurrentMapping
VideoMapping itsCurrentMapping
Current mapping, may not match any in itsMappings if setmapping2 used.
Definition: Engine.H:555
jevois::Engine::parseCommand
bool parseCommand(std::string const &str, std::shared_ptr< UserInterface > s, std::string const &pfx="")
Parse a user command received over serial port.
Definition: Engine.C:1705
jevois::Engine::~Engine
~Engine()
Destructor.
Definition: Engine.C:632
jevois::Engine::sendSerial
void sendSerial(std::string const &str, bool islog=false)
Send a string to all serial ports.
Definition: Engine.C:1132
jevois::Engine::module
std::shared_ptr< Module > module() const
Get a pointer to our current module (may be null)
Definition: Engine.C:1244
JEVOIS_IMUSPI_DEFAULT
#define JEVOIS_IMUSPI_DEFAULT
Default IMU spi device.
Definition: Engine.H:83
jevois::Engine::reloadVideoMappings
void reloadVideoMappings()
Re-load video mappings from videomappings.cfg.
Definition: Engine.C:448
jevois::Engine::getCurrentVideoMapping
const VideoMapping & getCurrentVideoMapping() const
Get the current video mapping.
Definition: Engine.C:1256
jevois::Engine::itsStopMainLoop
std::atomic< bool > itsStopMainLoop
Flag used to stop the main loop.
Definition: Engine.H:566
jevois::Engine::drawCameraGUI
void drawCameraGUI()
Draw all camera controls into our GUI.
Definition: Engine.C:2585
JEVOIS_SERIAL_DEFAULT
#define JEVOIS_SERIAL_DEFAULT
On platform hardware, device for the 4-pin hardware serial port.
Definition: Engine.H:73
jevois::Engine::itsGadget
std::shared_ptr< VideoOutput > itsGadget
Our IMU.
Definition: Engine.H:559
Enum.H