File: tutorial-synthetic-blenderproc.dox

package info (click to toggle)
visp 3.7.0-10
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid
  • size: 166,384 kB
  • sloc: cpp: 392,705; ansic: 224,448; xml: 23,444; python: 13,701; java: 4,792; sh: 207; objc: 145; makefile: 118
file content (850 lines) | stat: -rw-r--r-- 33,044 bytes parent folder | download
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
/**

\page tutorial-synthetic-blenderproc Tutorial: Generating synthetic data for deep learning with Blenderproc
\tableofcontents

\section dnn_synthetic_intro Introduction

In this tutorial, we will show how to generate synthetic data that can be used to train a neural network, thanks to
blenderproc.

Most of the (manual) work when training a neural network resides in acquiring and labelling data. This process can be
slow, tedious and error prone.
A solution to avoid this step is to use synthetic data, generated by a simulator/computer program. This approach comes
with multiple advantages:
- Data acquisition is fast
- It is easy to acquire accurate ground truth labels
- Variations in the training data can be easily added

There are however, some drawbacks:
- More knowledge of the scene is required: in the case of detection, we require a 3D model of the object, which is not
  the case for true images
- A difference between simulated and real data can be apparent and negatively impact network performance (this is
  called the Sim2Real gap)

The latter point is heavily dependent on the quality of the generated images and the more realistic the images, the
better the expected results.

Blender, using ray tracing, can generate realistic images. To perform data generation,
<a href="https://github.com/DLR-RM/BlenderProc">Blenderproc</a> has been developed and is an extremely useful and
flexible tool to generate realistic scenes from Python code.

Along with RGB images, Blenderproc can generate different labels or inputs:
- Depth map
- Normals
- Semantic segmentation
- Instance segmentation
- Bounding box
- Optical flow (not provided in our generation script)

In this tutorial, we will install blenderproc and use it to generate simple but varied scenes containing objects of
interest.
We provide a simple, object-centric generation script that should suffice in many cases.
However, since Blenderproc is easy to use, with many examples included in the
<a href="https://dlr-rm.github.io/BlenderProc/index.html">documentation</a>, readapting this script to your needs
should be easy.

\section dnn_synthetic_install Requirements

First, you should start by installing blenderproc. First, start by creating a new conda environment to avoid potential
conflicts with other Python packages.
\code{.sh}
$ conda create --name blenderproc python=3.10 pip
$ conda activate blenderproc
$ pip install blenderproc
\endcode
\note Our generation script has been tested with blenderproc 2.5.0 (with Blender 3.3 under the hood) and python 3.10.

You can then run the Blenderproc sample example with:
\code{.sh}
(blenderproc) $ blenderproc quickstart
\endcode
This may take some time, as Blenderproc downloads its own version of Blender and sets up its own environment.
This setup will only be performed once.

Once Blenderproc is done, you can check its output with:
\code{.sh}
(blenderproc) $ blenderproc vis hdf5 output/0.hdf5
\endcode


Blenderproc stores its output in HDF5 file format. Each HDF5 **may** contain the RGB image, along with depth, normals,
and other modalities.

For the simulator to provide useful data, we should obtain a set of realistic textures
(thus helping close the Sim2Real gap).
Thankfully, Blenderproc provides a helpful script to download a dataset of materials from cc0textures.com,
containing more than 1500 high resolution materials.
To download the materials, run
\code{.sh}
(blenderproc) $ blenderproc download cc_textures path/to/folder/where/to/save/materials
\endcode
\warning Because the materials are in high definition, downloading the full dataset may take a large amount of disk
space (30+ GB). If this is too much for you, you can safely delete some of the materials or stop the script after it
has acquired enough materials. While using a small number of materials can be useful when performing quick tests,
using the full set should be preferred as variety helps when transferring your deep learning model to real world data.


\section dnn_synthetic_script Running the object-centric generation script

We will now run the generation script.
The script places a random set of objects in a simple cubic room, with added distractors. Materials of the walls and
distractors are randomized.

This script and an example configuration file can be found in the `script/dataset_generator` folder of your ViSP
<b>source</b> directory.

The basic algorithm is:
\verbatim
For each scene:
  Choose N target objects from the provided models
  Add noise to the N objects (material properties, size, geometry)
  Generate a scene:
    - compute s = length of the larget diagonal of the axis-aligned bounding box of the largest object
    - set room_size = s * random_scale_factor
    - Create the ground, walls and ceiling of the room (with size room_size) and select a random material for each of them
    - Add random distractors, sampled from spheres, cubes, cylinders and monkey heads (Suzanne)
    For each distractor:
      - Sample a random position and orientation in the room
      - Select a random material from cc0
      - Add noise to PBR
      - Potentially add displacement
      - Potentially set distractor as emissive (emitting light)
    - Add random lights, either point lights or spots
    For each light:
      - Sample a random intensity and position
      - Sample a random color
      - If the light is a spot, orient it so that it focuses on a target object
    If simulating physics:
      - Simulate physics for a fixed time and set final object poses
    Remove objects that left the room (Physics collisions)
  Sample camera poses:
    For each sample to generate:
      Do while camera pose is not correct:
        - Select a target object
        - Select a point of interest in the bounding box of the object
        - Sample a random camera location in a clamped ball around the object
          - Camera position is set to have a minimum/maximum distance to the point of interest that is dependent on the object size
        - Set camera orientation to look at the point of interest, with a random rotation around the optical axis
        - Camera pose is correct if target object is visible and camera does not clip through an object or a wall
  - Call blender rendering
  - Save data in HDF5 format
    - If required, compute occlusion-aware bounding boxes
    - If required, save object pose in camera frame
\endverbatim
Many randomization parameters can be modified to alter the rendering, as explained in \ref dnn_input_configuration.

With this simple approach, we can obtain images such as:
\image html misc/blenderproc_rgb_example.png

\subsection dnn_input_objects 3D model format
To use this data generation tool, you should first provide the 3D models.
You can provide multiple models, which will be sampled randomly during generation.

The models should be contained in a folder as such:
\verbatim
- models
  - objectA
    - model.obj
    - model.mtl
    - texture.png
  - objectB
    - another_model.obj
    - another_model.mtl
\endverbatim

When setting up the configuration file in \ref dnn_input_configuration, "models_path" should point to the root folder,
models.
Each subfolder should contain a single object, in `.obj` format (with potential materials and textures). Each object
will be considered as having its own class, the class name being the name of the subfolder (e.g., objectA or objectB).
The class indices start with 1, and are sorted alphabetically depending on the name of the class (e.g., objectA = 1,
objectB = 2).

\subsection dnn_input_configuration Generation configuration
Configuring the dataset generation is done through a JSON file. An example configuration file can be seen below:
\include example_config.json

The general parameters are:
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>numpy_seed</td>
    <td>Int</td>
    <td>Seed for numpy's random functions. Allows for reproducible results.</td>
  </tr>
  <tr>
    <td>blenderproc_seed</td>
    <td>String</td>
    <td>Seed for Blenderproc. Allows for reproducible results.</td>
  </tr>
  <tr>
    <td>models_path</td>
    <td>String</td>
    <td>Path to the folder containing the models. See \ref dnn_input_objects</td>
  </tr>
  <tr>
    <td>cc_textures_path</td>
    <td>String</td>
    <td>Path to the folder containing the CC0 materials.</td>
  </tr>
</table>

You can also control some of the rendering parameters. This will impact the rendering time and the quality of the
generated RGB images.
These parameters are located in the "rendering" field.
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>max_num_samples</td>
    <td>Int > 0</td>
    <td>Number of rays per pixels. A lower number results in noisier images (especially in scenes with large variations).</td>
  </tr>
  <tr>
    <td>denoiser</td>
    <td>One of [null, "INTEL", "OPTIX"]</td>
    <td>Which denoiser to use after performing ray tracing. null indicates that no denoiser is used. "OPTIX" requires
    a compatible Nvidia GPU.
    Using a denoiser allows to obtain a clean image, with a low number of rays per pixels.</td>
  </tr>
</table>

You can also modify the camera's intrinsic parameters. The camera uses an undistorted perspective projection model.
For more information on camera parameters, see vpCameraParameters.
These parameters are found in the "camera" field of the configuration.
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>px</td>
    <td>Float</td>
    <td>See vpCameraParameters</td>
  </tr>
  <tr>
    <td>py</td>
    <td>Float</td>
    <td>See vpCameraParameters</td>
  </tr>
  <tr>
    <td>v0</td>
    <td>Float</td>
    <td>See vpCameraParameters</td>
  </tr>
  <tr>
    <td>u0</td>
    <td>Float</td>
    <td>See vpCameraParameters</td>
  </tr>
  <tr>
    <td>h</td>
    <td>Int</td>
    <td>Height of the generated images.</td>
  </tr>
  <tr>
    <td>w</td>
    <td>Int</td>
    <td>Width of the generated images.</td>
  </tr>
  <tr>
    <td>randomize_params_percent</td>
    <td>Float, [0, 100)</td>
    <td>
      Controls the randomization of the camera parameters \f$p_x, p_y, u_0, v_0\f$. If randomize_params_percent > 0,
      then, each time a scene is created the intrinsics are perturbed around the given values.
      For example, if this parameters is equal to 0.10 and \f$p_x = 500\f$, then the used \f$p_x\f$ when generating
      images will be in the range [450, 550].
    </td>
  </tr>
</table>


To customize the scene, you can change the parameters in the "scene" field:
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>room_size_multiplier_min</td>
    <td>Float > 1.0, < room_size_multiplier_max</td>
    <td>
      Minimum room size as a factor of the biggest sampled target object. The room is cubic.
      The size of the biggest object is the length of the largest diagonal of its axis-aligned bounding box.
      This tends to overestimate the size of the object.
      If the size of the biggest object is 0.5m, room_size_multiplier_max = 2 and room_size_multiplier_max = 4,
      then the room's size will be randomly sampled to be between 1m and 2m.
    </td>
  </tr>
  <tr>
    <td>room_size_multiplier_max</td>
    <td>Float > room_size_multiplier_min</td>
    <td>
      Minimum room size as a factor of the biggest sampled target object. The room is cubic.
      The size of the biggest object is the length of the largest diagonal of its axis-aligned bounding box.
      This tends to overestimate the size of the object.
      If the size of the biggest object is 0.5m, room_size_multiplier_max = 2 and room_size_multiplier_max = 4,
      then the room's size will be randomly sampled to be between 1m and 2m.
    </td>
  </tr>

  <tr>
    <td>simulate_physics</td>
    <td>Boolean</td>
    <td>Whether to simulate physics. If false, then objects will be floating across the room. If true,
    then objects will fall to the ground.</td>
  </tr>
  <tr>
    <td>max_num_textures</td>
    <td>Int > 0</td>
    <td>Max number of textures per blenderproc run. If scenes_per_run is 1, max_num_textures = 50 and the number of
    distractors is more than 50, then the 50 textures will be used across all distractors (and walls). In this case,
    new materials will be sampled for each scene.</td>
  </tr>
  <tr>
    <td>distractors</td>
    <td>Dictionary</td>
    <td>See below</td>
  </tr>
  <tr>
    <td>lights</td>
    <td>Dictionary</td>
    <td>See below</td>
  </tr>
  <tr>
    <td>objects</td>
    <td>Dictionary</td>
    <td>See below</td>
  </tr>
</table>

Distractors are small, simple objects that are added along with the target objects to create some variations and
occlusions. You can also load custom objects as distractors.
To modify their properties, you can change the "distractors" field of the scene
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>min_count</td>
    <td>Int >= 0, < max_count</td>
    <td>
      Minimum number of distractors to place in the room.
    </td>
  </tr>
  <tr>
    <td>max_count</td>
    <td>Int > min_count</td>
    <td>
      Maximum number of distractors to place in the room.
    </td>
  </tr>
  <tr>
    <td>custom_distractors</td>
    <td>string, or null</td>
    <td>
      If not null, path to a folder containing custom distractor objects, in .obj or .ply format.
    </td>
  </tr>
  <tr>
    <td>custom_distractor_proba</td>
    <td>float, >= 0.0, <= 1.0 </td>
    <td>
      If custom_distractors is not null, probability that a distractor is sampled from the user specified distractors.
    </td>
  </tr>
  <tr>
    <td>min_size_rel_scene</td>
    <td>Float > 0.0</td>
    <td>
      Minimum size of the distractors, relative to the room size.
      If the room size is 0.5m and min_size_rel_scene = 0.1, then the minimum size of distractor will be 0.05m.
      Scale is applied independently on each axis.
    </td>
  </tr>
  <tr>
    <td>max_size_rel_scene</td>
    <td>Float < 1.0, > min_size_rel_scene</td>
    <td>
      maximum size of the distractors, relative to the room size.
      If the room size is 0.5m and max_size_rel_scene = 0.2, then the maximum size of distractor will be 0.1m.
      Scale is applied independently on each axis.
    </td>
  </tr>
  <tr>
    <td>displacement_max_amount</td>
    <td>Float >= 0.0 </td>
    <td>
      Amount of displacement to apply to distractors.
      Displacement subdivides the mesh and displaces each of the distractor's vertices according to a random noise
      pattern.
      <b>This option greatly slows down rendering: set it to 0 if needed.</b>
    </td>
  </tr>
  <tr>
    <td>pbr_noise</td>
    <td>Float >= 0.0 </td>
    <td>
      Amount of noise to add to the material properties of the distractors.
      These properties include the specularity, the "metallicness" and the roughness of the material, according to
      Blender's principled BSDF.
    </td>
  </tr>
  <tr>
    <td>emissive_prob</td>
    <td>Float >= 0.0 , <= 1.0</td>
    <td>
      Probability that a distractor becomes a light source: its surface emits light. Set to more than 0 to add more
      light variations and shadows.
    </td>
  </tr>
  <tr>
    <td>emissive_min_strength</td>
    <td>Float >= 0.0, < emissive_max_strength</td>
    <td>
      Minimum emission strength for a distractor that emits lights. In Watts/m².
    </td>
  </tr>
  <tr>
    <td>emissive_max_strength</td>
    <td>Float > emissive_min_strength</td>
    <td>
      Maxmimum emission strength for a distractor that emits lights. In Watts/m².
    </td>
  </tr>
</table>

To change the lighting behaviour, see the options below:
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>min_count</td>
    <td>Int >= 0, < max_count</td>
    <td>
      Minimum number of lights in the scene.
    </td>
  </tr>
  <tr>
    <td>max_count</td>
    <td>Int > min_count</td>
    <td>
      Maximum number of lights in the scene
    </td>
  </tr>
  <tr>
    <td>min_intensity</td>
    <td>Float > 0.0, < max_intensity</td>
    <td>
      Minimum intensity of a light. In Watts.
    </td>
  </tr>
  <tr>
    <td>max_intensity</td>
    <td>Float > min_intensity</td>
    <td>
      Maximum intensity of a light. In Watts.
    </td>
  </tr>
</table>

To change the sampling behaviour of target objects, see the properties below:
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>min_count</td>
    <td>Int >= 0, < max_count</td>
    <td>
      Minimum number of target objects in the scene.
    </td>
  </tr>
  <tr>
    <td>max_count</td>
    <td>Int > min_count</td>
    <td>
      Maximum number of target objects in the scene.
    </td>
  </tr>
  <tr>
    <td>multiple_occurences</td>
    <td>Boolean</td>
    <td>
      Whether a single object can appear multiple times in the same scene (sampling with replacement).
    </td>
  </tr>
  <tr>
    <td>scale_noise</td>
    <td>Float >= 0.0</td>
    <td>
      Object size noise. if scale_noise > 0.0, the object is scaled uniformly on all axes (it does not appear stretched)
    </td>
  </tr>
  <tr>
    <td>displacement_max_amount</td>
    <td>Float >= 0.0 </td>
    <td>
      Amount of displacement to apply to target objects.
      Displacement subdivides the mesh and displaces each of the distractor's vertices according to a random noise pattern.
      <b>This option greatly slows down rendering: set it to 0 if needed.</b>
      Note that this is in absolute units: and does not vary depending on the size of the object.
    </td>
  </tr>
  <tr>
    <td>pbr_noise</td>
    <td>Float >= 0.0 </td>
    <td>
      Amount of noise to add to the material properties of the target objects.
      These properties include the specularity, the "metallicness" and the roughness of the material, according to
      Blender's principled BSDF.
    </td>
  </tr>
  <tr>
    <td>cam_min_dist_rel</td>
    <td>Float >= 0.0, < cam_max_dist_rel </td>
    <td>
      Minimum distance of the camera to the point of interest of the object when sampling camera poses.
      This is expressed in terms of the size of the target object.
      If the target object has a size of 0.5m and cam_min_dist_rel = 1.5, then the closest possible camera will be
      at 0.75m away from the point of interest.
    </td>
  </tr>
  <tr>
    <td>cam_max_dist_rel</td>
    <td>Float >= cam_min_dist_rel</td>
    <td>
      Maximum distance of the camera to the point of interest of the object when sampling camera poses.
      This is expressed in terms of the size of the target object.
      If the target object has a size of 0.5m and cam_max_dist_rel = 2.0, then the farthest possible camera will
      be 1m away from the point of interest.
    </td>
  </tr>
</table>

Finally, we can customize the dataset that we will generate from the given scenes.
This includes the number of scenes, images, and what information to save.

All the data will be stored in HDF5 format, which can then be unpacked later.

To customize the dataset, modify the options in the "dataset" field:
<table>
  <tr><th>Name</th><th>Type, possible values</th><th>Description</th></tr>
  <tr>
    <td>save_path</td>
    <td>String</td>
    <td>Path to the folder that will contain the final dataset. This folder will contain one folder per scene,
    and each sample of a scene will be its own HDF5 file.</td>
  </tr>
  <tr>
    <td>scenes_per_run</td>
    <td>Int > 0</td>
    <td>
      Number of scenes to generate per blenderproc run. Between blenderproc runs, Blender is restarted in order to
      avoid memory issues.
    </td>
  </tr>
  <tr>
    <td>num_scenes</td>
    <td>Int > 0</td>
    <td>
      Total number of scenes to generate. Generating many scenes will add more diversity to the dataset as object
      placement, materials and lighting are randomized once per scene.
    </td>
  </tr>
  <tr>
    <td>images_per_scene</td>
    <td>Int > 0</td>
    <td>
      Number of images to generate per scene. The total number of samples in the dataset will be
      num_scenes * (images_per_scene + empty_images_per_scene).
    </td>
  </tr>
  <tr>
    <td>empty_images_per_scene</td>
    <td>Int >= 0, <= images_per_scene</td>
    <td>
      Number of images without target objects to generate per scene. The camera poses for these images are sampled
      from the poses used to generate images with target objects. Thus, the only difference will be that the objects
      are not present, the rest of the scene is left untouched.
    </td>
  </tr>
  <tr>
    <td>pose</td>
    <td>Boolean</td>
    <td>
      Whether to save the pose of target objects that are visible in the camera. The pose of the objects are expressed
      in the camera frame as an homogeneous matrix \f$^{c}\mathbf{T}_{o}\f$
    </td>
  </tr>
  <tr>
    <td>depth</td>
    <td>Boolean</td>
    <td>
      Whether to save the depth buffer associated to the RGB image. Same size as the RGB image.
    </td>
  </tr>
  <tr>
    <td>normals</td>
    <td>Boolean</td>
    <td>
      Whether to save the normal map associated to the RGB image. Same size as the RGB image.
      The normals are 3D unit vectors, expressed in the camera frame.
    </td>
  </tr>
  <tr>
    <td>segmentation</td>
    <td>Boolean</td>
    <td>
      Whether to save the segmentation maps (by class and by instance).
      Segmentation by class only contains the target objects (class >= 1).
      Segmentation by instance includes every visible object.
    </td>
  </tr>
  <tr>
    <td>detection</td>
    <td>Boolean</td>
    <td>
      Whether to save the bounding box detections. In this case, bounding boxes are not computed from the segmentation
      map (also possible with Blenderproc), but rather in way such that occlusion does not influence the final bounding box.
      The detections can be filtered with the parameters in "detection_params".
    </td>
  </tr>
  <tr>
    <td>detection_params:min_size_size_px</td>
    <td>Int >= 0</td>
    <td>
      Minimum side length of a detection for it to be considered as valid. Used to filter really far or small objects,
      for which detection would be hard.
    </td>
  </tr>
  <tr>
    <td>detection_params:min_visibility</td>
    <td>Float [0.0, 1.0]</td>
    <td>
      Percentage of the object that must be visible for a detection to be considered as valid. The visibility score is
      computed as such:
      First, the vertices of the mesh that are behind the camera are filtered. Then, the vertices that are outside of
      the camera's field of view are filtered. Then, we randomly sample "detection_params:points_sampling_occlusion"
      points to test whether the object is occluded (test done through ray casting).
      If too many points are filtered, then the object is considered as not visible and detection is invalid.
    </td>
  </tr>
</table>


\section dnn_run_script Running the script to generate data

Once you have configured the generation to your liking, navigate to the `script/dataset_generator` located in your
ViSP source directory.

You can then run the `generate_dataset.py` script as such
\code{.sh}
(blenderproc) user@machine:~/visp/script/dataset_generator $ python generate_dataset.py --config path/to/config.json
\endcode

If all is well setup, then the dataset generation should start and run.


\warning If during generation, you encounter a message about invalid camera placement, try to make
room_size_multiplier_min and room_size_multiplier_max larger, so that more space is available for object placement.

To give an idea of generation time, generating 1000 images (with a resolution of 640 x 480) and detections of a
single object, with a few added distractors, takes around 30mins on a Quadro RTX 6000.

Once generation is finished, you are ready to leverage the data to train your neural network.

\section dnn_output Using and parsing the generation output

The dataset generated by Blender is located in the "dataset:save_path" path that you specified in your JSON
configuration file.

The dataset has the following structure
\verbatim
- dataset
  - 0
    - 0.hdf5
    - 1.hdf5
    - ...
  - 1
    - 0.hdf5
    - 1.hdf5
    - ...
  - ...
  - classes.txt
\endverbatim

There is one subfolder per scene, and each HDF5 file is a single sample that may contain RGB, depth, normals, etc.

You can visualise the generated images (RGB, depth, normals, segmentation maps) by running
\code{.sh}
(blenderproc) $ blenderproc vis hdf5 path/to/your/output/0/*.hdf5
\endcode

You will then see something that looks like this, depending on the outputs that you chose in the configuration file:
\image html blenderproc_viz.png

where you can replace the "0" in the path with another number, which corresponds to the generated scene index.
You can also specify the path to a single HDF5 file to view one sample at a time.

\subsection dnn_output_yolov7 Using detections to finetune a YoloV7

To help, we provide a script that reformats a blenderproc dataset to the format expected by YoloV7.
This script can be run like this:
\code{.sh}
(blenderproc) $ python export_for_yolov7.py --input path/to/dataset --output path/to/yolodataset --train-split 0.8
\endcode

here "--input" indicates the path to the location of the blenderproc dataset, while "--output" points to the folder
where the dataset in the format that YoloV7 expects will be saved. "--train-split" is an argument that indicates how
much of the dataset is kept for training. A value of 0.8 indicates that 80% of the dataset is used for training,
while 20% is used for validation. The split is performed randomly across all scenes (a scene may be visible in both
 train and validation sets).

Once the script has run, the folder "path/to/yolodataset" should be created and contain the dataset as expected by YoloV7.
This folder contains a "dataset.yml" file, which will be used when training a YoloV7. It contains:
the following:

```
names:
- esa
nc: 1
train: /local/user/yolov7_esa_dataset/images/train
val: /local/user/yolov7_esa_dataset/images/val
```
where nc is the number of class, "names" are the class names, and "train" and "val" are the paths to the dataset splits.

To start training a YoloV7, you should download the <a href="">repository</a> and install the required dependencies.
Again, we will create a conda environment. You can also use a docker container, as explained in the documentation.
We also download the pretrained yolo model, that we will finetune on our own dataset.
```
~ $ git clone https://github.com/WongKinYiu/yolov7.git
~ $ cd yolov7
~/yolov7 $ conda create --name yolov7 pip
~/yolov7 $ conda activate yolov7
(yolov7) ~/yolov7 $ pip install -r requirements.txt
(yolov7) ~/yolov7 $ wget https://github.com/WongKinYiu/yolov7/releases/download/v0.1/yolov7-tiny.pt
```

\warning While creating the yolov7 virtual environment, you may face the following error:
"requirements to build wheel did not run successfully". It can be solved by fixing the version of the Python of
the virtual environment: `conda create --name yolov7 pip python=3.10`

To fine-tune a YoloV7, we should create two new files: the network configuration and the hyperparameters.
We will reuse the ones provided for the tiny model.
```
CFG=cfg/training/yolov7-tiny-custom.yaml
cp cfg/training/yolov7-tiny.yaml $CFG

HYP=data/hyp.scratch.custom.yaml
cp data/hyp.scratch.tiny.yaml $HYP
```
Next open the new cfg file, and modify the number of classes (set "nc" from 80 to the number classes you have in your dataset).

You can also modify the hyperparameters file to add more augmentation during training.

To fine-tune the YoloV7-tiny on our data, run
```
YOLO_DATASET=/path/to/dataset
IMG_SIZE=640
YOLO_NAME=blenderproc-tiny
python train.py --workers 8 --device 0 --batch-size 64 --data "${YOLO_DATASET}/dataset.yaml" --img $IMG_SIZE $IMG_SIZE --cfg $CFG --weights yolov7-tiny.pt --name  $YOLO_NAME --hyp $HYP
```

Note that if your run fine-tuning multiple times, then a number will be appended to the name that you have given to your model.

If you run out of memory during training, change the batch size to a lower value.

Here is an overview of the generated images and the resulting detections for a simple model (cube) and a NeRF-reconstructed one:
\htmlonly
<p align="center">
<iframe width="560" height="315" src="https://www.youtube.com/embed/ftCLH96Rh0g" title="YouTube video player" frameborder="0" allow="accelerometer; autoplay; clipboard-write; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
<iframe width="560" height="315" src="https://www.youtube.com/embed/8t1P7Q7iP2w" title="YouTube video player" frameborder="0" allow="accelerometer; autoplay; clipboard-write; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
</p>
\endhtmlonly

\subsection dnn_output_custom_parsing Parsing HDF5 with a custom script

In Python, an HDF5 file can be read like a dictionary.

With the following script, you can inspect the content of an HDF5 file:
\code{.py}
from pathlib import Path
import numpy as np
import h5py
import json

if __name__ == '__main__':
  dataset_path = Path('output')
  for scene_folder in dataset_path.iterdir():
    if not scene_folder.is_dir():
      continue
    print(f'Reading scene {scene_folder.name}')
    for sample in scene_folder.iterdir():
      if not sample.name.endswith('.hdf5'):
          continue
      print(f'\tReading sample {sample.name}')
      with h5py.File(sample) as f:
          # Image data
          keys = ['colors', 'depth', 'normals', 'class_segmaps', 'instance_segmaps']
          for key in keys:
             if key in f:
                data = np.array(f[key])
                print(f'\t\t{key}: shape = {data.shape}, type = {data.dtype}')
          # Json objects
          if 'instance_attribute_maps' in f:
            print('\t\tMapping between instance and class:')
            text = np.array(f['instance_attribute_maps']).tobytes()
            json_rep = json.loads(text)
            print(json_rep)
            print()

          if 'object_data' in f:
            text = np.array(f['object_data']).tobytes()
            json_rep = json.loads(text)

            for object_idx, object_data in enumerate(json_rep):
              print(f'\t\tObject {object_idx} data: ')
              for obj_k in object_data.keys():
                print(f'\t\t\t{obj_k} = {object_data[obj_k]}')
              print()
\endcode

Running on a custom dataset with all outputs enabled (see \ref dnn_input_configuration) we obtain the following output:
\verbatim
...
Reading scene 4
  Reading sample 0.hdf5
    colors: shape = (480, 640, 3), type = uint8
    depth: shape = (480, 640), type = float32
    normals: shape = (480, 640, 3), type = float32
    class_segmaps: shape = (480, 640), type = uint8
    instance_segmaps: shape = (480, 640), type = uint8
    Mapping between instance and class:
      [{'idx': 5, 'category_id': 2}, {'idx': 7, 'category_id': 3}, {'idx': 10, 'category_id': 0}, {'idx': 11, 'category_id': 0},
       {'idx': 14, 'category_id': 0}, {'idx': 18, 'category_id': 0}, {'idx': 22, 'category_id': 0}, {'idx': 32, 'category_id': 0},
       {'idx': 37, 'category_id': 0}]

    Object 0 data:
      class = 2
      name = cube.001
      cTo = [[-0.9067991971969604, -0.12124679982662201, 0.40374961495399475, 0.06561152129493264],
            [-0.399792343378067, 0.5511342883110046, -0.7324047088623047, 0.31461843930247957],
            [-0.1337185800075531, -0.8255603313446045, -0.548241913318634, 0.01648345626311576],
            [0.0, 0.0, 0.0, 1.0]]
      bounding_box = [138.9861569133729, 254.62236838239235, 100.20349472431002, 107.79005297420909]

    Object 1 data:
      class = 3
      name = dragon.002
      cTo = [[-0.9067991971969604, -0.12124679982662201, 0.40374961495399475, 0.06561152129493264],
             [-0.399792343378067, 0.5511342883110046, -0.7324047088623047, 0.31461843930247957],
             [-0.1337185800075531, -0.8255603313446045, -0.548241913318634, 0.01648345626311576],
             [0.0, 0.0, 0.0, 1.0]]
      bounding_box = [314.54058632091767, 202.86607727119753, 70.64506150004479, 90.54480823214647]
...
\endverbatim

- Both depth and normals are represented as floating points, conserving accuracy.
- The object data is represented as a JSON document. Which you can directly save or reparse to save only the
  information of interest.
- Object poses are expressed in the camera frame and are represented as homogeneous matrix.
- Bounding boxes coordinates are in pixels, and the values are [x_min, y_min, width, height]

You can modify this script to export the dataset to another format, as it was done in \ref dnn_output_yolov7.

\section dnn_synthetic_next Next steps

If you use this generator to train a detection network, you can combine it with Megapose to perform 6D pose estimation
and tracking. See \ref tutorial-tracking-megapose.

*/