99 lines
4.4 KiB
Markdown
99 lines
4.4 KiB
Markdown
|
# Leopard Imaging LI-M021C-MIPI Stereo-Optic Cameras
|
||
|
|
||
|
## Kernel Changes
|
||
|
The source code we have modified or added and is pertinent to these cameras is in the following files:
|
||
|
* controls-utility.sh
|
||
|
* hardware/nvidia/platform/t18x/common/kernel-dts/t18x-common-platforms/tegra186-tx2-spiri-camera-base.dtsi
|
||
|
* hardware/nvidia/platform/t18x/common/kernel-dts/t18x-common-platforms/tegra186-tx2-spiri-camera.dtsi
|
||
|
* hardware/nvidia/platform/t18x/quill/kernel-dts/Makefile
|
||
|
* hardware/nvidia/platform/t18x/quill/kernel-dts/tegra186-tx2-spiri-USB3.dts
|
||
|
* hardware/nvidia/platform/t18x/quill/kernel-dts/tegra186-tx2-spiri-base.dts
|
||
|
* hardware/nvidia/platform/t18x/quill/kernel-dts/tegra186-tx2-spiri-mPCIe.dts
|
||
|
* hardware/nvidia/platform/t18x/quill/kernel-dts/tegra186-tx2-spiri-revF+.dts
|
||
|
* nvidia/drivers/media/i2c/mt9m021.c
|
||
|
* nvidia/drivers/media/i2c/mt9m021_mode_tbls.h
|
||
|
* nvidia/drivers/media/platform/tegra/camera/camera_common.c
|
||
|
* nvidia/drivers/media/platform/tegra/camera/tegracam_ctrls.c
|
||
|
* nvidia/include/media/camera_common.h
|
||
|
* nvidia/include/media/tegra-v4l2-camera.h
|
||
|
|
||
|
All these modifications and additions are part of the Spiri Mu kernel, and are represented by symbolic links from this repository into https://git.spirirobotics.com/Spiri/mu_kernel_sources, with the exception of the controls-utility.sh script, which is transferred in the spiri_scripts folder of the rootfs.
|
||
|
|
||
|
## Features
|
||
|
|
||
|
* V4L2 Kernel Driver Version 2.0 supported on L4T32.2.1
|
||
|
* V4l2 controls
|
||
|
* test pattern
|
||
|
* individual gains
|
||
|
* vertical/horizontal flip
|
||
|
* flash control
|
||
|
* LibArgus and nvarguscamerasrc
|
||
|
* Resolution supported: 1280x720 @ 60fps
|
||
|
* Gain, exposure, and framerate controls
|
||
|
* Camera synchronization
|
||
|
|
||
|
## Capture Tests
|
||
|
|
||
|
### Frame-rate Tests
|
||
|
|
||
|
* Set the framerate to 60fps and the driver will configure the sensor:
|
||
|
```
|
||
|
gst-launch-1.0 nvarguscamerasrc sensor-id=0 aelock=true awblock=true ! 'video/x-raw(memory:NVMM), width=(int)1280, height=(int)720, format=(string)NV12,framerate=(fraction)60/1' ! fakesink
|
||
|
```
|
||
|
|
||
|
* Set the framerate to 45fps and the driver will configure the sensor:
|
||
|
```
|
||
|
gst-launch-1.0 nvarguscamerasrc sensor-id=0 aelock=true awblock=true ! 'video/x-raw(memory:NVMM), width=(int)1280, height=(int)720, format=(string)NV12,framerate=(fraction)45/1' ! fakesink
|
||
|
```
|
||
|
|
||
|
### UDP Streaming Test
|
||
|
#### Sender Endpoint
|
||
|
```
|
||
|
gst-launch-1.0 nvarguscamerasrc ! 'video/x-raw(memory:NVMM), width=(int)1280, height=(int)720, format=(string)NV12,framerate=(fraction)30/1' ! omxh264enc control-rate=2 bitrate=8000000 ! 'video/x-h264, stream-format=(string)byte-stream' ! h264parse ! rtph264pay mtu=1400 ! udpsink host=$HOST_IP port=5000 sync=false async=false
|
||
|
```
|
||
|
|
||
|
#### Receiver Endpoint
|
||
|
```
|
||
|
gst-launch-1.0 udpsrc port=5000 ! "application/x-rtp,media=(string)video,payload=(int)96,clock-rate=(int)90000,encoding-name=(string)H264" ! rtph264depay ! queue ! avdec_h264 ! xvimagesink sync=true async=false
|
||
|
```
|
||
|
|
||
|
### Set Controls Test
|
||
|
Run a pipeline, then set gain and exposure controls using v4l2-ctl:
|
||
|
```
|
||
|
v4l2-ctl -d /dev/video1 -c exposure=14000
|
||
|
v4l2-ctl -d /dev/video1 -c gain=100
|
||
|
```
|
||
|
|
||
|
### Dual Synchronized Capture Test
|
||
|
First run the master pipeline and then the slave pipeline:
|
||
|
|
||
|
#### Master Pipeline
|
||
|
```
|
||
|
gst-launch-1.0 nvarguscamerasrc sensor-id=0 aelock=true awblock=true ! 'video/x-raw(memory:NVMM), width=(int)1280, height=(int)720, format=(string)NV12,framerate=(fraction)60/1' ! fakesink
|
||
|
```
|
||
|
|
||
|
#### Slave Pipeline
|
||
|
```
|
||
|
gst-launch-1.0 nvarguscamerasrc sensor-id=1 aelock=true awblock=true ! 'video/x-raw(memory:NVMM), width=(int)1280, height=(int)720, format=(string)NV12,framerate=(fraction)60/1' ! fakesink
|
||
|
```
|
||
|
|
||
|
It is not recommended to start both streams at the same time, because nvarguscamerasrc will fail if no buffers arrive on a defined timeout.
|
||
|
|
||
|
### V4l2 Capture Test
|
||
|
#### Master
|
||
|
```
|
||
|
v4l2-ctl -d /dev/video0 --set-fmt-video=width=1280,height=720,pixelformat=RG12 --set-ctrl bypass_mode=0 --stream-mmap
|
||
|
```
|
||
|
|
||
|
#### Slave
|
||
|
```
|
||
|
v4l2-ctl -d /dev/video01 --set-fmt-video=width=1280,height=720,pixelformat=RG12 --set-ctrl bypass_mode=0 --stream-mmap
|
||
|
```
|
||
|
|
||
|
## Documentation
|
||
|
* <a href="https://nextcloud.spirirobotics.com/f/3369">CSI2 adapter board guide</a>
|
||
|
* <a href="https://nextcloud.spirirobotics.com/f/3382">Camera module data sheet</a>
|
||
|
* <a href="https://nextcloud.spirirobotics.com/f/3392">Camera sensor data sheet</a>
|
||
|
* <a href="https://nextcloud.spirirobotics.com/f/3396">Camera sensor development guide</a>
|
||
|
* <a href="https://nextcloud.spirirobotics.com/f/3386">MIPI bridge</a>
|