Tutorial: Docking with Nova Carter Using Nav2 and FoundationPose in Sim

Prerequisites

  1. Finish the Tutorial for FoundationPose with Isaac Sim.

  2. Download a pre-trained SyntheticaDETR model for AMR:

    cd ${ISAAC_ROS_WS}/isaac_ros_assets/models/synthetica_detr &&  \
      wget 'https://api.ngc.nvidia.com/v2/models/nvidia/isaac/synthetica_detr/versions/1.0.0_onnx/files/sdetr_amr.onnx'
    

Instructions

  1. Set up Isaac Sim:

https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/main/resources/isaac_ros_docs/robots/nova_carter/set_up_isaac_sim.gif/
  • Install and launch Isaac Sim following the Isaac ROS Isaac Sim Setup Guide.

  • Add the charging dock at the path /localhost/NVIDIA/Assets/Isaac/4.2/Isaac/Props/NVIDIA/Carter/ChargingDock/charging_station_galileo.usd to the Isaac ROS Sample scene.

  • Adjust docking and robot transforms as desired. For example: set dock to (-10.0, 14.0, 0.01, 0.0, 0.0, 180) and set robot to (-2.0, 14.0, 0.0, 0.0, 0.0, 180).

  • Select /World/Nova_Carter_ROS/ros_lidars/publish_front_2d_lidar_scan in the Stage pane and change the topic name for front 2D Lidar as shown below.

    https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/main/resources/isaac_ros_docs/concepts/localization/lidar/isaac_sim_lidar_topic.png/
  • Select /World/Nova_Carter_ROS/ros_lidars/front_2d_lidar_render_product in the Stage pane and set enabled to True (checked).

  • Select /World/Nova_Carter_ROS/ros_lidars/front_3d_lidar_render_product in the Stage pane and set enabled to False (unchecked).

  • Press Play to initiate data publishing from Isaac Sim.

  1. Build and install the required packages:

  1. Make sure you followed the Prerequisites and you are inside the Isaac ROS Docker container.

  2. Install the prebuilt Debian package:

    sudo apt-get update
    
    sudo apt-get install -y ros-humble-nova-carter-bringup
    
  1. Continuing inside the Docker container, convert the model (.onnx) to a TensorRT engine plan:

    /usr/src/tensorrt/bin/trtexec --onnx=${ISAAC_ROS_WS}/isaac_ros_assets/models/synthetica_detr/sdetr_amr.onnx --saveEngine=${ISAAC_ROS_WS}/isaac_ros_assets/models/synthetica_detr/sdetr_amr.plan
    
  2. Run the launch file:

    ros2 launch nova_carter_docking docking_with_fp_sim.launch.py init_pose_x:=-2.0 init_pose_y:=14.0 init_pose_yaw:=3.14
    

    Note

    Verify that you see an RViz2 window open. In RViz2, change the Detection3DArray topic name to /tracking/output to display the 3D pose estimation bounding box overlaid on the input image.

  3. Send a docking action:

    ros2 action send_goal /dock_robot opennav_docking_msgs/action/DockRobot "
    {
        use_dock_id: false,
        dock_pose: {
            pose: {
            position: {x: -10.0, y: 14.0, z: 0.0},
            orientation: {x: 0.0, y: 0.0, z: 1.0, w: 0.0}
            },
            header: {
            frame_id: 'map'
            }
        },
        dock_type: 'nova_carter_dock',
        navigate_to_staging_pose: true
    }"
    
https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/main/resources/isaac_ros_docs/robots/nova_carter/docking_with_fp_sim.gif/

Docking with Nova Carter in Isaac Sim Using FoundationPose

Troubleshooting

  1. If the Nova Carter does not establish contact with the dock after the docking process is complete, consider adjusting the external_detection_translation_x parameter in /workspaces/isaac_ros-dev/src/nova_carter/nova_carter_docking/params/nova_carter_docking_fp.yaml. The default value is -0.15. You may increase this value to bring the Nova Carter closer to the dock. More details for docking parameters can be found on GitHub.

  2. If you encounter a situation where the robot cannot complete the docking goal using FoundationPose, it may be due to the limited performance of your workstation. In our example, we are using a workstation with the following specifications:

    • CPU: Intel Core i9-14900K, 24 cores, 6.0 GHz

    • GPU: NVIDIA RTX 6000 Ada Generation

    • RAM: 128 GB DDR5

    We rely on pose estimation at the staging location and dock using the tracking results. As the robot gets closer to the dock, detection becomes unreliable due to the limited field of view. To address this, you may need to increase the reset_period parameter in the launch file here or consider launching the fp_dock_pose_publisher in the launch file here separately at the staging location when the pose estimation is accurate.