DriveWorks SDK Reference
3.5.78 Release
For Test and Development only

/dvs/git/dirty/gitlab-master_av/dw/sdk/tools/calibration/doc/dwx_camera_calibration.md
Go to the documentation of this file.
1 # Copyright (c) 2019-2020 NVIDIA CORPORATION. All rights reserved.
2 
3 @page dwx_camera_calibration Static Camera Calibration
4 @tableofcontents
5 
6 @note SW Release Applicability: This tutorial is applicable to modules in both **NVIDIA DriveWorks** and **NVIDIA DRIVE Software** releases.
7 
8 The NVIDIA<sup>&reg;</sup> Static Camera Calibration tutorial describes how to perform intrinsic and extrinsic calibration for a vehicle's cameras using the DriveWorks Static Calibration Tools.
9 
10 The step-by-step tutorial covers the following:
11 - @ref dwx_camera_calibration_prereq : The materials required to perform calibration.
12 - @ref dwx_camera_calibration_setup : The proper camera and target placements.
13 - @ref dwx_camera_calibration_data : Capturing the intrinsic and extrinsic data required for the tools.
14 - @ref dwx_camera_calibration_tooling : Generating camera calibration output.
15 - @ref dwx_camera_calibration_additional_info : Additional Information including intrinsic-only calibration.
16 
17 @section dwx_camera_calibration_prereq 1.0 Prerequisites
18 
19 The following cameras and targets are required before proceeding in this tutorial.
20 
21 @subsection dwx_camera_calibration_prereq_cams 1.1 Cameras
22 
23 The following cameras are required for calibration:
24 
25 #### AV Cameras
26 
27 - N number of fixed focal length cameras. In this tutorial, 12 AR0231 cameras are used as an example.
28 - Cameras are mounted on vehicle or otherwise not expected to be purposely moved after completion of this tutorial.
29 - Referred to as "camera" or "cameras" throughout the remainder of this tutorial.
30 
31 #### One Camera to support AV camera calibration
32 
33 - Fixed focal length of roughly 18mm-30mm.
34 - At least 12MP resolution.
35 - Sensor size to be roughly Canon's ASP-C or Nikon's DX size (roughly 23mmx15mm).
36 - Referred to as "external camera" throughout the remainder of this tutorial.
37 
38 @subsection dwx_camera_calibration_prereq_targets 1.2 Targets
39 
40 This tutorial requires the use of targets to calibrate the vehicle's cameras.<br>
41 The targets used in this tutorial can be found in the following folder:
42 
43  data/tools/calibration/aprilTargets
44 
45 An example of the target used in this tutorial:
46 
47 ![Calibration Targets](patterns.png)
48 
49 @subsubsection dwx_camera_calibration_prereq_targets_prints 1.2.1 Target Prints
50 
51 The targets must be printed as follows:
52 
53 #### 8 large targets (or more)
54 - Size 1m x 1m.
55 - Target **IDs 89-101** in `data/tools/calibration/aprilTargets`.
56 
57 #### 4 small targets
58 - A3 format.
59 - Target **IDs 180-183** in `data/tools/calibration/aprilTargets`.
60 
61 @note A target with the same ID cannot be reused multiple times.
62 @note Although not recommended, it is possible to use targets other than the ones provided with the Static Calibration Tools.
63 
64 @subsubsection dwx_camera_calibration_prereq_targets_print_val 1.2.2 Target Print Validation
65 
66 For each target, measure the length of the horizontal bar in millimeters (mm) and note it in the corner, as demonstrated in the [above image](@ref dwx_camera_calibration_prereq_targets).
67 
68 @note Ensure the printouts have correct aspect ratios by comparing the length of the vertical and horizontal bars.
69 @note __If their lengths are not equal, the targets MUST be reprinted, as they do not have the correct aspect ratio.__
70 @note Additionally, ensure the targets are perfectly flat, rigid, and do not bend.
71 
72 <br>
73 @section dwx_camera_calibration_setup 2.0 Scene Setup
74 
75 @subsection dwx_camera_calibration_setup_cams 2.1 Camera Placement
76 
77 Depending on the number and location of the cameras on the vehicle, different scene setups may be used.<br>
78 In this tutorial, a setup with 12 cameras mounted on a car roof is used as an example.
79 
80 @subsection dwx_camera_calibration_setup_targets 2.2 Target Placement
81 
82 Ensure the following constraints when placing targets during scene setup:
83 
84 - The 4 [small targets](@ref dwx_camera_calibration_prereq_cams) are placed on the wheels, and that the target centers and wheel centers are aligned.
85 - Each camera requiring calibration must observe at least 1 [large target](@ref dwx_camera_calibration_prereq_cams).
86 - Each target covers the camera's field of view as much as possible.
87 - Each target is present only once in the scene.
88 
89 In this tutorial, a set of 8 large and 4 small targets are used as an example.
90 
91 ![Ideal Target Placement](targets_placement.png)
92 <br>
93 ![Example Target Placement](targets_placement2.png)
94 
95 @section dwx_camera_calibration_data 3.0 Capturing Data
96 
97 The following types of data must be captured for static camera calibration:
98 - **Intrinsic Data**: This only needs to be captured once if camera parameters i.e., lens, have not changed.
99 - **Extrinsic Data**: Includes images captured from the vehicle's cameras to be calibrated and images captured with the external camera.
100 
101 @subsection dwx_camera_calibration_data_int 3.1 Capturing Data for Intrinsic Camera Calibration
102 
103 To capture data for intrinsic camera calibration:
104 
105 1. Move a checkerboard pattern or AprilTag target in front of each camera requiring calibration.<br><br>
106 ![AprilTag in front of camera](intrinsic_calibration.png)
107 <br><br>
108 
109 2. Setup and start the Recorder for all cameras requiring calibration. Refer to @ref dwx_recording_devguide_basic_recording for more information how to setup recorder.
110 @note To save disc space setup recorder to record h264/mp4 stream directly, e.g. by passing `format=h264,output-format=yuv` as camera sensor properties. <br><br>
111 
112 3. While the recorder is running, perform the following for each camera:<br><br>
113  - Move the checkerboard pattern from left to right in front of the camera.
114  - While moving, rotate the pattern in all dimensions to calibrate pitch, roll, and yaw.
115  - While moving, get closer and further away from the camera to calibrate scale.
116  - Stop periodically while moving to allow motion-blur free constraint detection.
117 
118 The calibration tool will automatically extract all valid frames from the recorded video. \n Refer to @ref dwx_camera_calibration_tools_int.
119 
120 @subsection dwx_camera_calibration_data_ext 3.2 Capturing Data for Extrinsic Camera Calibration
121 
122 To capture data for extrinsic camera calibration, use one of the following methods to capture one image from each car camera:
123 
124 @subsubsection dwx_camera_calibration_dwksrecorder 3.2.1 Using the DriveWorks Recorder
125 
126 Use the DriveWorks Recorder Tool to simultaneously record video from all cameras and ffmpeg to extract one frame from the video.
127 
128 1. Setup the Driveworks Recorder Tool as described in @ref dwx_recording_devguide_basic_recording (use h264/mp4 recording)<br><br>
129 
130 2. Extract individual frames with ffmpeg:
131 
132  ffmpeg -i <folder>/camera_X.h264 -t 1 -f image2 camera_X.png
133 
134 @subsubsection dwx_camera_calibration_dwkssample 3.2.2 Using the DriveWorks Sample
135 
136 Use the DriveWorks Sample `sample_camera_multiple_gmsl` to capture a frame.
137 
138 1. For 12 cameras of the same type execute:
139 
140  ./sample_camera_multiple_gmsl --selector-mask=111111111111
141 <br>
142 2. Press **F** while the sample is running to capture a frame from each camera as a .png file.
143 
144 Once you have followed one of the two methods described above, rename and copy the files to an appropriate location as indicated by the [DriveWorks Calibration Tools](@ref dwx_camera_calibration_tooling).
145 
146 In addition to capturing frames from the vehicle's cameras, a set of images also needs to be captured with the external camera.<br>
147 These images help construct a calibration graph as they introduce a link between targets not observable by the car cameras.<br>
148 These targets can include ground targets, wheel targets, and between targets of individual cameras.
149 
150 It is recommended you capture at least 20 images with the external camera, so that all possible target pairs are recorded.<br>
151 Ensure these images simultaneously observe both the ground targets, and the wheel targets.
152 
153 The following demonstrates the types of images to capture with the external camera:
154 
155 ![Images to Capture with the External Camera](external_camera.png)
156 
157 @note It is not required to perform intrinsic calibration for the external camera. Targets detected in the frame will be automatically used for intrinsic constraints.
158 @note Therefore, it is important that there are at least 20 images provided for the external camera.
159 
160 @section dwx_camera_calibration_tooling 4.0 Using the Calibration Tools
161 
162 The Static Calibration Tool suite consists of multiple command line tools.
163 This tutorial covers the tools required for static calibration of the vehicle's cameras.
164 There are additional calibration tools for auxiliary support and additional sensor. These are not covered in this tutorial.
165 All tools used in this section are documented in @ref dwx_camera_calibration_tools.
166 
167 @note It is recommended to run the calibration tool suite on an x86 Host System due to the resource requirements of the internal optimization.
168 
169 @subsection dwx_camera_calibration_tools_dir 4.1 Directory Structure
170 
171 The calibration tools expect a specific directory structure as well as a predefined collection of files:
172 
173 ```
174  <calib-data-path>
175  |-- targets.json The target database with the measured bar lengths
176  |-- special-targets.json List all special targets in this file
177  |-- intrinsics Constraints generated using intrinsic tool
178  | |-- <camera-0>.json
179  | |-- ...
180  | |-- <camera-N>.json
181  |
182  |-- extrinsics Images captured by car cameras
183  | |-- <camera-0>.[png/jpg] NOTE: names of the files must match the .json
184  | |-- ... file names from the intrinsic/ folder
185  | |-- <camera-N>.[png/jpg]
186  |
187  |-- external Images captured by external camera
188  | |-- <image-0>.[png/jpg/JPG] NOTE: names of the images are irrelevant
189  | |-- ...
190  | |-- <image-M>.[png/jpg/JPG]
191 ```
192 
193 @subsubsection dwx_camera_calibration_targetsjson 4.1.1 targets.json
194 
195 **targets.json** is a target database shipped with DriveWorks. It contains all the large targets that can be used in the scene.
196 
197 Modify this file and change the `barLength` fields for all targets in the scene to the length (in meters) which you measured in @ref dwx_camera_calibration_prereq_targets_prints.
198 
199 @subsubsection dwx_coordinate_systems_specialtargets 4.1.2 special-targets.json
200 
201 **special-targets.json**: The targets attached to the wheels and the targets that lie flat on the floor must also be declared in this file.
202 
203 The structure of this file is as follows:
204 
205 ```
206 {
207  "ground_targets": [99,100],
208  "ignore_targets": [142],
209  "wheel_targets":
210  {
211  "rearLeft": 181,
212  "rearRight": 182,
213  "frontLeft": 180,
214  "frontRight": 183
215  }
216 }
217 ```
218 
219 Ensure that the targets which are on the ground and which are attached to the wheels are correctly identified in this file.
220 
221 @subsection dwx_camera_calibration_tools_int 4.2 Intrinsic Camera Calibration
222 
223 This section requires the usage of the DriveWorks @ref dwx_intrinsics_constraints, to extract intrinsics constraints used during calibration for each individual camera.<br>
224 The input for this tool is the video recorded in @ref dwx_camera_calibration_data_int.<br>
225 This tool will then export all required constraints and output them in a `.json` file to be placed in the `/intrinsics/` subfolder in the directory structure.
226 
227 @subsubsection dwx_camera_calibration_tools_11x8_board 4.2.1 For an 11x8 Checkerboard
228 
229 Run the tool by executing:
230 
231  ./calibration-intrinsics-constraints
232  --use-checkerboard=11x8
233  --input-video=<video_path>/camera-0.h264
234  --output=<calib_data_path>/intrinsics/camera-0.json
235 
236 @subsubsection dwx_camera_calibration_tools_apriltag_vid 4.2.2 For an AprilTag Target Video
237 
238 Run the tool by executing:
239 
240  ./calibration-intrinsics-constraints
241  --targetDB=<calib_data_path>/targets.json
242  --input-video=<video_path>/camera-0.h264
243  --output=<calib_data_path>/intrinsics/camera-0.json
244 
245 The tool will open a window playing back the input video and indicate with a red or green border if a new intrinsic constraint has been collected (i.e. target or checkerboard has been found).
246 
247 ![Intrinsics Constraints Output](intrinsic_constraints.png)
248 
249 @note It is important that the tool is able to find at least 30 constraints (checkerboards or AprilTags) per camera.
250 
251 @subsection dwx_camera_calibration_tools_ext 4.3 Extrinsic Calibration
252 
253 This section requires the usage of the DriveWorks @ref dwx_calibration_graph_cli, to construct a graph-based representation of the data obtained, which is then further optimized.
254 
255 Running this tool without parameters assumes you have the file structure specified in @ref dwx_camera_calibration_tools_dir.<br>
256 The tool determines the names of the cameras from the `extrinsics` folder. It then searches the `intrinsic` folder for `.json` files corresponding with the intrinsics constraints.<br>
257 The images captured with the external camera will also be used for intrinsic calibration for the external camera, and for extrinsics constraints.<br>
258 
259 The Calibration Tool will then use these images to construct a graph representation which is later optimized.
260 
261 @subsubsection dwx_camera_calibration_tools_ext_setup 4.3.1 Extrinsic Calibration Setup
262 
263 Ensure the following before proceeding:
264 
265 - The images captured in @ref dwx_camera_calibration_data_ext are placed in the `<calib_data_path>/extrinsics` folder. The image file \n names also match the intrinsics `.json` file names generated in @ref dwx_camera_calibration_tools_int.
266 
267 - The images captured by the external camera are placed in the `<calib_data_path>/external` folder.
268 
269 @subsubsection dwx_camera_calibration_tools_ext_exec 4.3.2 Extrinsic Calibration Execution
270 
271 Run the tool by executing the following:
272 
273  ./calibration-graph-cli --dir=<calib_data_path>
274 
275 The tool outputs progress to the console. Take note of warnings in yellow and errors in red as they indicate possible problems with the calibration.
276 
277 The following outputs are placed in the target folder:
278 
279 - `calibrated-graph.json` is the main output for this tool. This contains all constraints, the calibrated camera models, the camera poses, the target poses, etc.<br> This is an intermediate format which is meant for machine consumption only.
280 
281 - Intrinsic validation images show the set of points used for intrinsic calibration:
282  - Blue dots = detected.
283  - Red dots = reprojected.
284  - Small yellow lines = line joining detection and re-projection.
285  - Large yellow lines = outliers.
286 
287 The output is generated for all car cameras, (`validation-intrinsics-<camera>.jpg`) and the external cameras.
288 
289 ![Intrinsic Validation Output](intrinsic_validation.png)
290 
291 - Extrinsic validation images show the image used for extrinsic calibration with overlaid results, where:
292  - Detected targets have a green overlay.
293  - Detected tags have their corner detections with the same colors as their intrinsic re-projections.
294  - The ground plane is drawn as a series of green lines 1 meter apart. The lines at `x = 0` and `y = 0` are orange.
295 
296 The output is generated for all car cameras, and each external image (`validation-<camera>.jpg`).
297 
298 ![Extrinsic Validation Output](extrinsic_validation.png)
299 
300 @subsubsection dwx_camera_calibration_tools_ext_val 4.3.3 Extrinsic Calibration Validation
301 
302 Validation images can be used to double check if the computed calibration is valid, i.e., if the green re-projections match the targets.
303 
304 In the following image, a green mask clearly overlays the targets, and the corners are well aligned. This indicates a valid computed calibration.
305 
306 ![Valid Calibration](validation_good.png)
307 
308 In the following image, a green mask is misaligned with the target. This indicates the calibration results might not be correct, or that there is a problem with the calibration target.
309 
310 ![Invalid Calibration](validation_bad.png)
311 
312 @note In most cases an invalid re-projection of the calibration mask occurs when:
313 - Intrinsic calibration is not well constrained. This occurs if the checkerboard or target was not adequately covering the camera field of view during intrinsic calibration. As an example, intrinsic validation images contain points that are well-detected and spread all over.
314 - Target corner detection failed or is not precise. This may occur if the image is blurry or low quality.
315 - Targets are not flat. This is the most likely reason for the misalignment. Ensure that all targets are flat, rigid, and do not bend, to prevent these issues.
316 
317 @subsection dwx_camera_calibration_tools_rig 4.4 Generating DriveWorks `rig.json` File
318 
319 The @ref dwx_calibration_graph_cli also provides a `calibrated-graph.json` file as output. This file contains intermediate \n calibration results which cannot yet be consumed by the NVIDIA<sup>&reg;</sup> DriveWorks SDK. These results can be converted using the Calibrated Graph Tool into a valid DriveWorks SDK `rig.json` file representing the full calibrated camera rig configuration, and can be directly consumed by the DriveWorks modules, e.g., @ref rig_mainsection.
320 
321 To perform the conversion, run the tool by executing the following:
322 
323  ./calibration-graph-to-rig --graph=<calib_data_path>/calibrated-graph.json
324 
325 The tool generates a `rig.json` file in the current folder. This file lists all cameras used during calibration with their final intrinsic and extrinsic calibration data.
326 
327 ```
328 {
329  "rig": {
330  "sensors": [
331  {
332  "name": "CameraA",
333  "protocol": "camera",
334  "parameter": "",
335  "properties": {
336  "Model": "pinhole",
337  "cx": "960.00000",
338  "cy": "604.00000",
339  "distortion": "-3.38998615741730e-1 2.48174026608467e-1 0.000000000000000 ",
340  "fx": "1829.0598",
341  "fy": "1150.4340",
342  "height": "1208",
343  "width": "1920"
344  },
345  "correction_rig_T": [
346  0.0,
347  0.0,
348  0.0
349  ],
350  "correction_sensor_R_FLU": {
351  "roll-pitch-yaw": [
352  -2.9311993804404e-11,
353  1.66752689434446e-09,
354  -6.67010668919943e-09
355  ]
356  },
357  "nominalSensor2Rig_FLU": {
358  "roll-pitch-yaw": [
359  0.00125622225459665,
360  -0.0149850230664015,
361  0.0607732236385345
362  ],
363  "t": [
364  1.5044356584549,
365  -0.00227832840755582,
366  1.49242639541626
367  ]
368  }
369  },
370  ...
371  ],
372  "vehicle": {
373  "valid": false,
374  "value": {
375  "axlebaseFront": 0.0,
376  "axlebaseRear": 0.0,
377  "bumperFront": 0.0,
378  "bumperRear": 0.0,
379  "centerOfMassToRearAxle": 0.0,
380  "driveByWireTimeConstant": 0.0,
381  "driveByWireTimeDelay": 0.0,
382  "frontCorneringStiffness": 0.0,
383  "height": 0.0,
384  "inertia": 0.0,
385  "length": 0.0,
386  "mass": 0.0,
387  "rearCorneringStiffness": 0.0,
388  "steeringCoefficient": 0.0,
389  "wheelDiameter": 0.0,
390  "wheelbase": 0.0,
391  "width": 0.0,
392  "widthWithMirrors": 0.0
393  }
394  }
395  },
396  "version": 2
397 }
398 ```
399 
400 If an existing `rig.json` is passed as input, all camera entries are modified with the new calibration results.
401 
402 @note The coordinate system conventions used by the calibration tools can be found in @ref dwx_coordinate_systems.
403 
404 @section dwx_camera_calibration_additional_info 5.0 Additional Information
405 
406 @subsection dwx_camera_calibration_int_only 5.1 Intrinsic-only Calibration
407 
408 The Static Calibration Tool suite supports calibration for intrinsic parameters only, if extrinsic calibration is not desired or required.
409 
410 The procedure is similar to the full calibration workflow, with several modifications:
411 
412 1. Record videos with the checkerboard or AprilTag patterns described in @ref dwx_camera_calibration_data_int.
413 2. Create the directory structure as described in @ref dwx_camera_calibration_tools_dir. Only include the `intrinsics` folder and `targets.json` file.
414 3. For each camera, execute the [intrinsic calibration application](@ref dwx_camera_calibration_tools_int). This generates a set of `.json` files for each camera.
415 4. Execute the Graph Calibration Tool as demonstrated in @ref dwx_camera_calibration_tools_ext_exec.
416  - This generates a `calibrated-graph.json file` in the input directory, and intrinsic validation images as demonstrated in the section. Verify that these validation images meet the requirements described above.
417 5. Execute the Calibrated Graph to Rig File Tool to populate a `rig.json` file with the result. Refer to @ref dwx_camera_calibration_tools_rig for more information.