..
   Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved.
   NVIDIA CORPORATION and its licensors retain all intellectual property
   and proprietary rights in and to this software, related documentation
   and any modifications thereto. Any use, reproduction, disclosure or
   distribution of this software and related documentation without an express
   license agreement from NVIDIA CORPORATION is strictly prohibited.

Sensors Architecture: General Requirements
------------------------------------------

Multi-camera Calibration Requirements
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

======== ===================================================================================================================================================================
Req ID:  Coverage Overlap Requirements

27400300 For the purpose of extrinsic calibration between a pair of cameras in the camera belt, it is required to have sufficient coverage overlap between the two cameras.

         The overlap shall allow reliable detection of a checkerboard target with both cameras at the same target location, following Isaac extrinsic calibration procedure.

         The image below shows a successful detection of the target with one of the cameras.

         We have validated that a successful extrinsic calibration is achieved when the cameras have 25deg overlap of the covered field of view.

         
         .. figure:: :ir_lfs:`<resources/isaac_ros_docs/robots/nova_sensor_mounting_guide/multi_camera_coverage_overlap_reqs_1.png>`
         .. figure:: :ir_lfs:`<resources/isaac_ros_docs/robots/nova_sensor_mounting_guide/multi_camera_coverage_overlap_reqs_2.png>`


======== ===================================================================================================================================================================


Nominal values and URDF file generation
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

**Nominal values**

In cases when the mechanical assembly of the camera(s) arrangement can
meet angular tolerance requirement of ±1.6 degrees between any pair of
camera modules, Isaac software modules, including Isaac Perceptor, can
perform well provided a matching nominal calibration file in URDF
format.

The advantage of this approach is that it does not require calibration
between the camera modules and therefore reduces the time for Isaac
software evaluation.

**URDF file generation**

.. note::

   This section details the URDF creation process for `Nova Orin Developer Kit`, for illustration
   purposes only. It is not necessary to perform these steps if the sensors are mounted on the
   `Nova Orin Developer Kit` according to the table below. A default
   `xacro <https://index.ros.org/p/xacro/>`_ file is available in
   :ir_repo:`nova_developer_kit_macro.urdf.xacro <nova_developer_kit> <nova_developer_kit_description/urdf/nova_developer_kit_macro.urdf.xacro>`.
   
   If the `Nova Orin Developer Kit` is mounted on a robot, it is still necessary to provide a URDF
   encoding its position on the robot. Follow the instructions 
   :doc:`Mounting the Nova Orin Developer Kit on a Robot </reference_workflows/isaac_perceptor/run_perceptor_on_devkit>`.

The process of generation of ROS URDF nominal file follows the procedure
below:

Vortex (or principal point) nominal location and orientation should be
obtained from the vendor camera module documentation, for both stereo
and mono camera modules.

Camera modules should be positioned in an optimal way on the
target robot in the robot CAD model, following the guidelines and the
requirements of this design guide.

Vortex location and orientation of each camera module with respect to
the robot coordinate system should be summarized in a table of
six degrees of freedom.

Using this table, URDF file should be generated using a standard process
(the reader is referred to the available `ROS URDF documentation <https://wiki.ros.org/urdf>`_,
as well as to the xacro template examples for placing sensors on the `Nova Orin Developer Kit`
:ir_repo:`nova_developer_kit_macro.urdf.xacro <nova_developer_kit> <nova_developer_kit_description/urdf/nova_developer_kit_macro.urdf.xacro>`
and for placing the `Nova Orin Developer Kit` on a robot
:ir_repo:`nova_developer_kit.urdf.xacro <nova_developer_kit> <nova_developer_kit_description/urdf/nova_developer_kit.urdf.xacro>`).

The obtained URDF file should be referenced by Isaac software modules
following Isaac Perceptor documentation
(:doc:`Mounting the Nova Orin Developer Kit on a Robot </reference_workflows/isaac_perceptor/run_perceptor_on_devkit>`).

**Vertexes table example**

In this example we consider a rig that includes 3 Hawk camera and 3 Owl
cameras, as depicted in the image below:

.. figure:: :ir_lfs:`<resources/isaac_ros_docs/robots/nova_sensor_mounting_guide/multi_camera_vertexes_ex.png>`

The thick green arrow indicates the location of the rig vertex, aligned
with the center of the front Hawk camera, along the intersection line
between the bottom and the front Hawk planes.

The other six small Cartesian axes indicate the locations of the
vertexes of the six camera modules.

The figure also defines the rig coordinate system.

In this case, the vertex nominals table in rig coordinate system is
provided below:

============ ==== ==== ==== ===== ===== =====
Camera       X    Y    Z    Yaw   Pitch Roll

             [mm] [mm] [mm] [deg] [deg] [deg]
============ ==== ==== ==== ===== ===== =====
Hawk - Front -16  75   12.5 0     0     0
Hawk - Left  -165 106  12.5 90    0     0
Hawk - Right -15  -106 12.5 -90   0     0
Owl - Front  -10  0    38   0     0     0
Owl - Left   -90  112  38   90    0     0
Owl - Right  -90  -112 38   -90   0     0
============ ==== ==== ==== ===== ===== =====

The corresponding 
`xacro <https://index.ros.org/p/xacro/>`_ file for `Nova Orin Developer Kit`, as well as `Hawk`, and
`Owl` cameras are available in
:ir_repo:`nova_developer_kit_macro.urdf.xacro <nova_developer_kit> <nova_developer_kit_description/urdf/nova_developer_kit_macro.urdf.xacro>`,
:ir_repo:`hawk_macro.urdf.xacro <isaac_ros_nova> <hawk_description/urdf/hawk_macro.urdf.xacro>`,
and
:ir_repo:`owl_macro.urdf.xacro <isaac_ros_nova> <owl_description/urdf/owl_macro.urdf.xacro>`,
respectively.
The reader is advised to download Hawk and Owl specifications and 3D
models to cross-check these numbers.

**URDF Mounting the Nova Orin Developer Kit on a Robot**

.. _robot-urdf-with-nova-developer-kit:

If the `Nova Orin Developer Kit` is mounted on a robot, the user must provide a URDF encoding its
position on the robot.

It is recommended to follow the self-contained
:doc:`calibration instructions</robots/nova_carter/demo_calibration>`. The output of calibration is
stored in a default location in the robot, and Isaac Perceptor will use it without requiring any
additional arguments.

Alternatively, the remaining of this section details how to create a robot nominals URDF file
(``urdf_nominals_file_path``) to be used with Isaac Perceptor. Note that the steps below
shall not be followed if performing calibration. The instructions 
:doc:`Isaac Perceptor on a Robot with the Nova Orin Developer Kit</reference_workflows/isaac_perceptor/run_perceptor_on_devkit>`
detail how to provide the ``urdf_nominals_file_path`` to  Isaac Perceptor.

To define your own URDF nominals file to use in Isaac Perceptor, you can use the following code
snippet and store it at a suitable ``urdf_nominals_file_path``:

.. code-block:: xml

    <?xml version="1.0"?>
    <robot name="please_specify_robot_name" xmlns:xacro="http://www.ros.org/wiki/xacro">
    <xacro:arg name="robot_namespace" default="/"/> 
    <xacro:include filename="$(find nova_developer_kit_description)/urdf/nova_developer_kit_macro.urdf.xacro"/>

    <link name="base_link"/>
    <xacro:nova_developer_kit name="nova_developer_kit" parent="base_link" mount_is_root="true">
        <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
    </xacro:nova_developer_kit>
    </robot>

    <!-- Your Robot Description goes here. -->

The fields `xyz` and `rpy` parametrize the transformation between the
`Nova Orin Developer Kit` and the provided parent link (e.g. `base_link`). Specifically, the field `xyz`
represents a 3D translation in meters, and the field `rpy` represents a rotation as fixed-axis Euler
angles in radians: roll, pitch and yaw, respectively.

The field `mount_is_root` must be set to `true` if the transformation is provided with respect to
the `Nova Orin Developer Kit` mount point (center screw of the lower plate), or `false` if the
transformation refers to the `Nova Orin Developer Kit` main link (center-front of the module).

For example, if you are mounting the `Nova Orin Developer Kit` such that its center-front point is at a
height of `Z = 0.4 m` above the robot origin and `X = -0.1 m` behind it, the root link origin should
be adjusted accordingly:

.. code-block:: xml

    ...
    <xacro:nova_developer_kit name="nova_developer_kit" parent="base_link" mount_is_root="false">
        <origin xyz="-0.1 0.0 0.4" rpy="0.0 0.0 0.0"/>
    ...