neo_docking2 - Contour Matching Based Docking

neo_docking2 is a ROS 2 package and the spiritual successor of neo_docking.

Like neo_docking, neo_docking2 enables the Neobotix robot to autonomously dock with the charging station. However, unlike its predecessor, neo_docking2 does not rely on a depth camera or QR tags to detect the coordinates of the charging contacts. Instead, it uses contour matching—based on one of the ICP (Iterative Closest Point) methods—to determine the docking position. It also switches the safety fields of the Flexisoft system to proceed with docking.

Attention

This package is currently in beta. Documentation may change based on user feedback. If you have questions, please contact us via email or open an issue on the neo_docking2 GitHub repository.

The following instructions provide an overview of how the ROX robot docks with the Wallbox.

Attention

It is recommended to read the hardware documentation for the Wallbox before continuing with this tutorial.

Installation

  1. Install the ROS 2 PCL libraries. Open a terminal on the ROX robot and run:

    sudo apt install ros-$ROS_DISTRO-pcl-ros ros-$ROS_DISTRO-pcl-conversions
    
  2. Clone the neo_docking2 package:

    cd ~/ros2_workspace/src
    git clone https://github.com/neobotix/neo_docking2.git
    

    Switch to the branch automated-detection-flexi and check out the commit 4d08187.

    Note

    In the release version, the checkout step will be removed.

  3. Unzip the neo_perception2 zip file and add the folder containing the binaries to the install directory of your workspace.

Attention

neo_perception2 is a closed-source package. The version delivered with the Wallbox is restricted to detecting and docking with the Wallbox only.

  1. Source the installation package from the root of your workspace:

    cd ~/ros2_workspace
    . install/setup.base
    
  2. Build the package:

    colcon build --symlink-install
    
  3. Adjusting the navigation goal tolerance:

    In the navigation configuration, please make sure the xy_goal_tolerance is set to 0.01. The config files can be founder under ~/ros2_workspace/src/rox/rox_navigation/configs.

Parameters

Important

Do not change any of the preconfigured values provided for docking the ROX robot with the Wallbox.

  • auto_detect: Should be set to true.
  • scan_topic: The scanner topic used for contour matching.
  • undock_dist: The distance the robot travels during undocking. (Note: Undocking uses a simple P-controller.)
  • offset_x, offset_y: Define the target docking position relative to the map frame. The origin is the leftmost point of the detected contour. Provide the appropriate coordinates (in meters) for your docking configuration.
  • offset_yaw: Sets the orientation (in radians) for the docking transform to correctly align the robot with the docking station.

Available Services

  • /go_and_dock: Initiates the docking process.
  • /undock_and_arm: Initiates undocking and prepares the robot for the next command.
  • /perception/init_contour_pose: Sets the initial pose estimate for contour matching.

Prerequisites

It is highly recommended to have the Wallbox mapped to prevent even minor localization jumps.

Launching the Docking Process

  1. Position the Robot

    Place the robot in front of the docking station so that its front laser scanners can view the entire contour.

  2. Start the Docking Package

    Attention

    Ensure that the robot is localized and the necessary navigation bring-up has been completed.

    ros2 launch neo_docking2 docking_launch.py
    
  3. Provide an Initial Guess

    Use the /perception/init_contour_pose service to provide an initial estimate of the docking station’s position.

    ros2 service call /perception/init_contour_pose neo_srvs2/srv/InitializeContourMatching "{init_pose: {position: {x: 0.0, y: 0.0, z: 0.0}, orientation: {x: 0.0, y: 0.0, z: -0.08715, w: 0.9961}}}"
    

    Tip

    Have RViz open to ensure that the TFs are oriented as expected.

  4. Initiate Docking

    Ensure that the TF is correctly oriented as shown below before starting the docking process.

    ../_images/docking_start_pose.png
    ros2 service call /go_and_dock std_srvs/srv/Empty {}
    

    The robot will move to two predefined pre-docking positions. Pre-dock1 and pre-dock2 is reached using the Nav2 stack, whereas the docking position by itself is reached using a simple P-Controller.

    Note

    During navigation from the second pre-dock position to the final docking position, the robot will trigger a scanner stop. This is expected behavior. In the default safety mode (NONE) of the Flexisoft system, the safety fields are relatively long and wide, which can lead to a scanner stop. The docking node then transitions the Flexisoft to mode APPROACHING, which uses a safety field suitable for docking. In this mode, the Flexisoft performs contour matching again to verify alignment with the Wallbox before allowing the robot to proceed and dock.

    Once docking is complete, the front frame of the robot will be approximately 1 cm from the charging station, with a deviation of ±0.5 cm.

    Charging can be started using the service provided by the neo_relayboardv3 node as follows:

    ros2 service call /start_charging std_srvs/srv/Empty {}
    
  5. Undocking

    Before undocking from the Wallbox it is essential to stop the charging process:

    ros2 service call /stop_charging std_srvs/srv/Empty {}
    
    ros2 service call /undock_and_arm std_srvs/srv/Empty {}
    

    The robot will move away based on the user-specified undocking distance.

    Note

    During the undocking phase, the ROS node switches the safety mode of the flexisoft to DEPARTING. Here the flexisoft once again checks for the contour to making sure the user is undocking from the wallbox. Once undocking is finished, the safety mode NONE is once again set by the ROS 2 node for docking.

Safety Notes

Warning

In the current version, we expect the wallbox to stay in the part of the mapped environment that does not change dynamically. If the mapped environment changes dynamically, there is a high probability that the docking will either be incomplete or end up touching the charging station, which is not ideal.