GMSL 2 Camera
Hardware
AutomatePro has an option of 0, 2 or 4 channel GMSL2 (Gigabit Multimedia Serial Link) camera link. GMSL2 is a robust high speed and low latency data link which was developed for automotive camera and display applications. It allows for cable lengths up to 15m and supports Power Over Coaxial (PoC). A maximum of 12W of power can be delivered through the AutomatePro to the downstream cameras. While other GMSL2 cameras can be used we recommend using those offered here. The number of FAKRA Z connectors populated will depend on the device ordered - see image below

Onboard GMSL2 Specifications
| Parameter | Value | 
|---|---|
| Onboard IC | MAX9296AGT | 
| Standard | GMSL2 | 
| Max Cable Length | 15m | 
| Max Data Rate | 4.5Gbs | 
| PoC Voltage | 12VDC | 
| FAKRA Type | Type Z (Water Blue) | 
| Max Power (total) | 12W | 
ROS API
Node: automatepro_cam1_driver, automatepro_cam2_driver
Publishers
| Topic | Type | Description | 
|---|---|---|
| /camera/camera_name/image_raw | sensor_msgs/msg/Image | Contains Image frame. | 
| /camera/camera_name/camera_info | sensor_msgs/msg/CameraInfo | Contains camera info. | 
| /camera/camera_name/h264/video | foxglove_msgs/msg/CompressedVideo | Contains h264 compressed video frame. | 
| /camera/camera_name/h264/calib | foxglove_msgs/msg/CameraCalibration | Contains camera calibration info. | 
Parameters
| Parameter | Type | Values | Runtime R/W | Description | 
|---|---|---|---|---|
| frame_id | string | cam1/cam2 | read-only | The frame sensor data messages. | 
| camera_name | string | cam1/cam2 | read-only | Unique name for the camera. | 
| resolution | int[2] | [640,512] | read-only | Output resolution of the /image_raw,  upto[1536, 1920] | 
| compression.enable | bool | true/false | read-only | Enable video compression. | 
| compression.format | string | h264 | read-only | Compression Format (Currently supports h264only) | 
| compression.bitrate | int | 5000 | read-only | Max bitrate in kbits per second, driver will reduce quality to keep the bitrate below the set max limit | 
| compression.keyframe | int | 30 | read-only | No of frames between transmitting the keyframes | 
Configuration
Cameras are controlled using the V4L2 API and are exposed as /dev/video0 and /dev/video1 devices. Below is a description for using
the automatepro_camera_driver, but these cameras can be used with any standard drivers, which support V4L2 devices.
More details are available here.
Driver: automatepro_camera_driver
Container: automatepro-core-driver
All the configuration related files can be found at /opt/automatepro/config/ros directory.
These files will be mounted to docker container and will be used by the ROS driver.
Environmental variables can be set in the /opt/automatepro/.env file.
config file can be found here.
/automatepro/config/ros/camera_params.yaml
Default Config
automatepro_cam1_node:
  ros__parameters:
    camera_name: "cam1"
    camera_info_url: ""
    resolution: [640, 512]
    format: "bgr8"
    frame_id: "cam1"
    compression:
      enable: true
      format: "h264"
      bitrate: 5000    # kbps
      keyframe: 30
    # Do not change the following parameters
    sensor:
      device: "/dev/video0"
      model: "SG3S-ISX031C"
      resolution: [1920, 1536]
      frame_rate: 30
      format: "UYVY"
automatepro_cam2_node:
  ros__parameters:
    camera_name: "cam2"
    camera_info_url: ""
    resolution: [640, 512]
    format: "bgr8"
    frame_id: "cam2"
    compression:
      enable: true
      format: "h264"
      bitrate: 5000    # kbps
      keyframe: 30
    # Do not change the following parameters
    sensor:
      device: "/dev/video1"
      model: "SG3S-ISX031C"
      resolution: [1920, 1536]
      frame_rate: 30
      format: "UYVY"
Restart the automatepro-core-driver docker container after changing the configuration.
Configurations will only be applied after the container restarts.
docker restart automatepro-core-driver
Using other drivers
To use the cameras with different drivers, you need to disable the automatepro_camera_driver.
Edit the /opt/automatepro/.env file and set the ROS_DRIVER_CAM1 and ROS_DRIVER_CAM2 to false.
Restart the automatepro-core-driver container to apply the changes.
sudo systemctl restart automatepro-core-driver
Now, you can use the cameras with any standard V4L2 driver, OpenCV, GStreamer, or any other camera driver. For more details on hardware acceleration and GStreamer, check the NVDIA Jetson documentation.
Troubleshooting
if you are facing any issues with the camera, restart the automatepro-gmsl2.service
sudo systemctl stop automatepro-core-driver
sudo systemctl restart automatepro-gmsl2.service
Then restart the automatepro-core-driver container to apply the changes.
sudo systemctl start automatepro-core-driver