Tutorial: Docking with Nova Carter in Sim and Real
This tutorial demonstrates docking using AprilTag. AprilTags are a system of visual tags that provide low overhead, high accuracy localization.
If you are not interested in using AprilTag, see the tutorial on docking with FoundationPose:
Prerequisites
Ensure an AprilTag is affixed to the front of the dock to allow the robot to accurately detect the dock’s position. The AprilTag must belong to the tag36h11 family and measure 6 inches. The image below illustrates how to measure the tag size. For further information about AprilTags, see the details provided here.
Docking with Nova Carter in Isaac Sim Using AprilTag
Set up Isaac Sim:
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.Select
/World/Nova_Carter_ROS/ros_lidars/front_2d_lidar_render_product
in the Stage pane and setenabled
to True (checked).Select
/World/Nova_Carter_ROS/ros_lidars/front_3d_lidar_render_product
in the Stage pane and setenabled
to False (unchecked).Press Play to initiate data publishing from Isaac Sim.
AprilTag attachment and configuration:
The following image illustrates the attachment of the AprilTag to the dock in the simulation environment. The default dock is equipped with four AprilTags. The following steps configure the AprilTag for docking:
Select an AprilTag: Choose one of the four AprilTags to scale.
Adjust Parameters: Scale the selected AprilTag using the parameters shown in the image below.
Hide Remaining Tags: Make the other three AprilTags invisible.
Build and install the required packages:
Make sure you followed the Prerequisites and you are inside the Isaac ROS Docker container.
Install the prebuilt Debian package:
sudo apt-get update
sudo apt-get install -y ros-humble-nova-carter-bringup
Make sure you followed the Prerequisites and you are inside the Isaac ROS Docker container.
Use
rosdep
to install the package’s dependencies:sudo apt-get update
rosdep update && rosdep install --from-paths ${ISAAC_ROS_WS}/src/nova_carter/nova_carter_bringup --ignore-src -y
Build the package from source:
cd ${ISAAC_ROS_WS}/ && \ colcon build --symlink-install --packages-up-to nova_carter_bringup \ --packages-skip isaac_ros_peoplesemseg_models_install
Source the ROS workspace:
Note
Make sure to repeat this step in every terminal created inside the Docker container.
Because this package was built from source, the enclosing workspace must be sourced for ROS to be able to find the package’s contents.
source install/setup.bash
Run the launch file:
ros2 launch nova_carter_docking docking_with_apriltag_sim.launch.py init_pose_x:=-2.0 init_pose_y:=14.0 init_pose_yaw:=3.14
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 }"
Docking with Nova Carter in Real Using AprilTag
Attach the AprilTag to the dock.
The image below illustrates the attachment of the AprilTag to the dock in the real-world environment:
SSH into the robot (instructions). Make sure you have successfully connected the PS5 joystick to the robot (instructions).
Build and install the required packages:
Pull the docker image:
docker pull nvcr.io/nvidia/isaac/nova_carter_bringup:release_3.2-aarch64
Run the docker image:
docker run -it --privileged --network host \ -v /dev/*:/dev/* \ -v /tmp/argus_socket:/tmp/argus_socket \ -v /etc/nova:/etc/nova \ nvcr.io/nvidia/isaac/nova_carter_bringup:release_3.2-aarch64 /bin/bash
Make sure you followed the Prerequisites and you are inside the Isaac ROS Docker container.
Install the prebuilt Debian package:
sudo apt-get update
sudo apt-get install -y ros-humble-nova-carter-bringup
Make sure you followed the Prerequisites and you are inside the Isaac ROS Docker container.
Use
rosdep
to install the package’s dependencies:sudo apt-get update
rosdep update && rosdep install --from-paths ${ISAAC_ROS_WS}/src/nova_carter/nova_carter_bringup --ignore-src -y
Build the package from source:
cd ${ISAAC_ROS_WS}/ && \ colcon build --symlink-install --packages-up-to nova_carter_bringup \ --packages-skip isaac_ros_ess_models_install isaac_ros_peoplesemseg_models_install
Source the ROS workspace:
Note
Make sure to repeat this step in every terminal created inside the Docker container.
Because this package was built from source, the enclosing workspace must be sourced for ROS to be able to find the package’s contents.
source install/setup.bash
Run the launch file for your cloud services configuration:
ros2 launch nova_carter_docking docking_with_apriltag_real.launch.py \
map_yaml_path:=<path_to_map_yaml>
ros2 launch nova_carter_bringup navigation.launch.py \
enable_nvblox_costmap:=False \
stereo_camera_configuration:=front_driver_rectify \
enable_wheel_odometry:=True \
enable_3d_lidar_localization:=True \
map_yaml_path:=<path_to_map_yaml> \
enable_mission_client:=True \
mqtt_host_name:=<mission_dispatch_ip>
Note
You must replace <path_to_map_yaml>
with the path of the map YAML
file. If you do not have a map of your environment you can create one using
the Lidar mapping tutorial
Obtain an initial pose for your dock.
The docking server uses this dock pose to calculate an approximate initial pose for dock detection. Precise measurements are not necessary.
Use the PS5 joystick to maneuver the Nova Carter into the dock. Open a new terminal in the container and execute:
ros2 run tf2_ros tf2_echo map base_link
Verify that you receive output similar to the following:
- Translation: [45.199, 19.320, 0.000] - Rotation: in Quaternion [0.000, 0.000, 0.614, 0.789] - Rotation: in RPY (radian) [0.000, -0.000, 1.323] - Rotation: in RPY (degree) [0.000, -0.000, 75.787]
Record the Translation and Rotation in Quaternion for later use.
Send a docking action appropriate for your cloud services configuration:
ros2 action send_goal /dock_robot opennav_docking_msgs/action/DockRobot "
{
use_dock_id: false,
dock_pose: {
pose: {
position: {x: 45.199, y: 19.320, z: 0.0},
orientation: {x: 0.0, y: 0.0, z: 0.614, w: 0.789}
},
header: {
frame_id: 'map'
}
},
dock_type: 'nova_carter_dock',
navigate_to_staging_pose: true
}"
Follow the directions to start Isaac Mission Dispatch.
Verify that Mission Dispatch is running, by navigating to
http://localhost:5000/docs
orhttp://<your_ip_address>:5000/docs
.Note
Read this deployment tutorial for more deployment options for Mission Dispatch.
Send the docking mission command.
dock_robot
action parameters (types of all parameters arestring
):Parameter
Description
dock_type
The type of dock. For Nova Carter, it is
nova_carter_dock
.dock_pose
The position of the dock. A comma separated string with three floats. For example, for the sample pose shown in step 5, it is
45.199,19.320,1.323
.trigger_global_localization
Optional. Whether to trigger global localization before executing the action. It is
true
by default.Use the dock pose you get from step 5. Here is an example input for mission dispatch:
{ "robot": "carter01", "mission_tree": [ { "name": "dock", "parent": "root", "action": { "action_type": "dock_robot", "action_parameters": { "dock_type": "nova_carter_dock", "dock_pose": "<dock_x>,<dock_y>,<dock_yaw>", "trigger_global_localization": "true" } } } ], "timeout": 300, "deadline": "2023-09-28T04:04:24.013Z", "needs_canceled": false, "name": "dock_example" }
Note
The robot state does not turn to
CHARGING
, if the battery percentage is high (around 90%).Send the undocking mission. (Optional)
undock_robot
action parameters (types of all parameters arestring
):Parameter
Description
dock_type
The type of dock. For Nova Carter, it is
nova_carter_dock
.trigger_global_localization
Optional. Whether to trigger global localization after executing the action. It is
true
by default. In the default Nova Carter configuration, global localization relies on the front 2D Lidar. This can lead to positional drift when Nova Carter is docked. It is recommended to enable this.Here is an example input for mission dispatch:
{ "robot": "carter01", "mission_tree": [ { "name": "undock", "parent": "root", "action": { "action_type": "undock_robot", "action_parameters": { "dock_type": "nova_carter_dock", "trigger_global_localization": "true" } } } ], "timeout": 300, "deadline": "2023-09-28T04:04:24.013Z", "needs_canceled": false, "name": "undock_example" }
Note
The robot can still perform undocking when the state is not
CHARGING
. Nav2 Collision detection is disabled when the robot is in-between the staging pose and the dock. The path between staging pose and the dock is expected to be free of obstacles.
Troubleshooting
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.yaml
.
The default value is -0.18
. You may increase this value to bring the Nova Carter closer to the dock.
More details for docking parameters can be found on GitHub.