.. attention:: **Read this document carefully!** In case of doubt, consult specialists, experts, or manufacturers of the assemblies used. The robot **must not be operated** before all uncertainties are clarified. For further assistance, refer to the guides below or contact a specialist. **Important**: Contact information is available in the RMA/ Support Section. **Warning**: Do not allow untrained individuals or those unfamiliar with robotics or these instructions to operate the robot. Improper use of robots is dangerous. This guide will walk you through the process of setting up and configuring the Unitree H1 robot, including network configurations, SSH access, internet setup, software installation and various operational controls. Follow the steps below carefully to ensure proper operation. .. _robot_interface: Robot Interface =============== Instructions for interfacing with the robot using **Ubuntu 20.04** and **ROS2 Foxy**. This procedure should be followed **after** successfully setting up and pairing with the H1 robot. Additionally, all of the H1’s functionality should be verified through the accompanying app before proceeding. The **Ethernet port**, located beneath the right arm of the H1 (the fourth port from the top), can be used to establish communication via LAN. However, a **special adapter cable** is required, as a standard Ethernet cable cannot be inserted directly into the port. +-------------------------------------------------------+-------------------------------------------------------+ | .. figure:: media/figures/h1_ethernetport.jpg | .. figure:: media/figures/h1_ethernet_port.png | | :width: 40% | :width: 70% | | :align: center | :align: center | | :alt: Brush Teleoperation | :alt: Port Location (Layout Diagram) | | | | | Port Location on H1 (Real Robot) | Port Location (Layout Diagram) | +-------------------------------------------------------+-------------------------------------------------------+ | .. figure:: media/figures/h1_ethernet_adapter.png | .. figure:: media/figures/h1_ethernet_adapter_1.png | | :width: 40% | :width: 100% | | :align: center | :align: center | | :alt: Ethernet Adapter | :alt: Ethernet Adapter Cable Ends | | | | | Ethernet Adapter | Ethernet Adapter Cable Ends | +-------------------------------------------------------+-------------------------------------------------------+ Network Setup ============= To configure the robot's network for the first time, you need to connect using a **LAN** cable. To create a static connection on your **PC** (not on the robot), follow these steps in **Ubuntu**: 1. Go to **Settings** → **Network**, then click on the **+** button to create a new connection. 2. In the **IPv4** settings, change the connection type to **Manual**. 3. Set the **Address** to **192.168.123.51** and the **Netmask** to **24**. 4. Click **Save**, then restart your network. After successfully connecting, check the host's local IP by typing the following command in the host PC's terminal: .. code-block:: bash ifconfig Now, ping the robot by entering: .. code-block:: bash ping 192.168.123.162 To access the robot via SSH, use the following command: .. code-block:: bash ssh -X unitree@192.168.123.162 The default password is: .. code-block:: bash Unitree0408 IP Addresses ============ +------------------------+--------------------+------------+ | **Robot** | **IP Address** |**Password**| +========================+====================+============+ | H1 MCU | 192.168.123.161 | - | +------------------------+--------------------+------------+ | H1 External | 192.168.123.162 | 123 | +------------------------+--------------------+------------+ | H1 Livox Mid360 | 192.168.123.120 | - | +------------------------+--------------------+------------+ .. note:: Sometimes other networks can cause disruptions when connecting to the H1. It is best to have only your connection to the robot active and disable all others. Quick-Setup =========== Powering-on ----------- .. figure:: media/figures/h1_power_on.jpg :width: 35% :align: center **Battery Power Button**: Use the buttons on both batteries to power on the robot. To power on the H1 robot, press the power button on **both batteries simultaneously** once, and then press and hold for **3 seconds** to start the robot. The battery compartments are located beneath the **left arm** of the robot. Similarly, to turn off the robot, press the power button on **both batteries simultaneously** once, and then press and hold for **3 seconds** to turn off the robot. .. note:: Please be cautious with battery consumption. Continuously monitor the battery levels. If any battery is depleted, the robot will fall. Robot Control Setup =================== - First, connect to the H1 as described in the :ref:`robot_interface` section. - Next, open multiple SSH sessions into the H1 using the following command: .. code-block:: bash ssh -X unitree@192.168.123.162 - Verify that the robot is processing information by typing the following command in one of the SSH sessions: .. code-block:: bash ros2 topic echo /lowstate - If data is displayed, it indicates that the Unitree drivers are running. Drivers Setup ============= All ROS2 drivers for the H1 developed by MYBOTSHOP operate with the environment variable **ROS_DOMAIN_ID=10**. To start the custom Mybotshop ROS2 drivers for the H1, run the following command: .. note:: Please ensure that the robot's arms are straight down when you power on the robot. If the arms are in a different orientation, it may affect the ROS2 control operations. .. code-block:: bash ros2 launch h1_bringup system.launch.py This command starts the driver for operating the H1 in high-level mode for the legs and arms. .. important:: The arms will initialize and move so that the forearms are facing forward. The H1 ROS2 driver includes the following components: - Domain Bridge - Joint States - Robot Description - Arm Control - Leg Control (High-level) - Inertial Measurement Unit Publisher - Sensor Fusion - Twist Mux - Logitech F710 Control - D435i Depth Camera Driver - Livox Mid360 LiDAR Driver - 2D Scanner Visualization Tools =================== You can view the H1's current state by entering the following command in one of the SSH sessions: .. code-block:: bash ros2 launch h1_viz view_robot.launch.py .. figure:: media/figures/h1_viz.png :width: 100% :align: center H1 Robot Visualization in RViz Teleoperation ============== To teleoperate the H1, run the following command in one of the SSH sessions: .. code-block:: bash ROS_DOMAIN_ID=10 ros2 run teleop_twist_keyboard teleop_twist_keyboard Steamdeck Integration ===================== .. important:: The Lidar data and camera stream are dependent on the DDS configuration and the WiFi dongle being used. **Setup Instructions:** 1. Before launching the H1 bringup, run the following command on the H1: .. code-block:: bash ros2_wifi 2. Launch the system: .. code-block:: bash ros2 launch h1_bringup system.launch.py 3. Click on the joystick controller icon on the Steamdeck to access controls. **Controls:** *Leg Control:* - Slow Movement: `L1` + Left Joystick - Right Movement: `R1` + Left Joystick *Arm Control:* - To be announced (TBA). This can be modified using the `h1_steamdeck libjoy`. Leg Control Mode ================ The following H1 modes are available via ROS2 services: .. code-block:: bash - damp - stand_switch - increase_swing_height - decrease_swing_height - enable_ctrl .. note:: Pressing the **Tab** key on the keyboard will autocomplete the service request. Example of Activating a Mode ---------------------------- To activate a specific mode, use the following command: .. code-block:: bash ROS_DOMAIN_ID=10 ros2 service call /h1/leg_modes h1_srvs/srv/H1Modes '{"request_data": "stand_switch"}' Arm Low-Level Control ===================== The predefined arm positions do not include obstacle avoidance for either the robot or its environment. .. Important:: Ensure that the arms are straight down when powering on the robot. If the orientation is different, it will affect the ROS2 control operation. The arms will initialize and move so that the forearms are facing forward. To set the arms to their default position, use the following command: .. code-block:: bash h1_arm_default +-------------------------------------------------------+-------------------------------------------------------+ | .. figure:: media/gifs/arm_default.gif | .. figure:: media/gifs/arm_default_real.gif | | :width: 100% | :width: 90% | | :align: center | :align: center | | :alt: Executing arm default command | :alt: H1 arm moving to default position | | | | | Executing arm default command | H1 arm moving to default position | +-------------------------------------------------------+-------------------------------------------------------+ .. Warning:: Using the **h1_arm_zero** command brings the arms to a position that prevents backlash when restarting the ROS2 control driver. This should be done before closing the ROS2 driver if you plan to run the driver again later. To zero the arms, execute: .. code-block:: bash h1_arm_zero +-------------------------------------------------------+-------------------------------------------------------+ | .. figure:: media/gifs/arm_zero.gif | .. figure:: media/gifs/arm_zero_real.gif | | :width: 100% | :width: 90% | | :align: center | :align: center | | :alt: Executing arm zero command | :alt: H1 arm moving to zero position | | | | | Executing arm zero command | H1 arm moving to zero position | +-------------------------------------------------------+-------------------------------------------------------+ To set the arms to a T-pose, use: .. code-block:: bash h1_arm_t +-------------------------------------------------------+-------------------------------------------------------+ | .. figure:: media/gifs/arm_t.gif | .. figure:: media/gifs/arm_t_real.gif | | :width: 100% | :width: 90% | | :align: center | :align: center | | :alt: Executing T-pose command | :alt: H1 arm moving to T-pose | | | | | Executing T-pose command | H1 arm moving to T-pose | +-------------------------------------------------------+-------------------------------------------------------+ For a sample pose useful for picking objects, use: .. code-block:: bash h1_arm_pick +-------------------------------------------------------+-------------------------------------------------------+ | .. figure:: media/gifs/arm_pick.gif | .. figure:: media/gifs/arm_pick_real.gif | | :width: 100% | :width: 90% | | :align: center | :align: center | | :alt: Executing pick pose command | :alt: H1 arm moving to pick pose | | | | | Executing pick pose command | H1 arm moving to pick pose | +-------------------------------------------------------+-------------------------------------------------------+ Examples of Trajectory Control ------------------------------- Bring Left Arm to Zero Position ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ To bring the left arm to the zero position, run: .. code-block:: bash ROS_DOMAIN_ID=10 ros2 action send_goal /left_arm_controller/follow_joint_trajectory control_msgs/action/FollowJointTrajectory -f "{ trajectory: { joint_names: [left_shoulder_pitch_joint, left_shoulder_roll_joint, left_shoulder_yaw_joint, left_elbow_joint], points: [ { positions: [0.0, 0.0, 0.0, 0.0], time_from_start: { sec: 2 } }, { positions: [0.5, 0.0, 0.0, 0.1], time_from_start: { sec: 4 } }, ] } }" Bring Right Arm to Zero Position ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ To bring the right arm to the zero position, run: .. code-block:: bash ROS_DOMAIN_ID=10 ros2 action send_goal /right_arm_controller/follow_joint_trajectory control_msgs/action/FollowJointTrajectory -f "{ trajectory: { joint_names: [right_shoulder_pitch_joint, right_shoulder_roll_joint, right_shoulder_yaw_joint, right_elbow_joint], points: [ { positions: [0.0, 0.0, 0.0, 0.0], time_from_start: { sec: 2 } }, { positions: [0.5, 0.0, 0.0, 0.1], time_from_start: { sec: 4 } }, ] } }" To perform a final power-off of the arms, use: .. code-block:: bash h1_arm_zero +-------------------------------------------------------+------------------------------------------------------------+ | .. figure:: media/gifs/arm_goal.gif | .. figure:: media/gifs/arm_goal_real.gif | | :width: 100% | :width: 85% | | :align: center | :align: center | | :alt: Executing trajectory control to zero position| :alt: H1 arm transitioning from T-pose to zero position | | | | | Executing trajectory control to zero position | H1 arm transitioning from T-pose to zero position | +-------------------------------------------------------+------------------------------------------------------------+ MoveIt2 Integration =================== To launch the H1 MoveIt2 driver, run: .. code-block:: bash ros2 launch h1_moveit system.launch.py This will open MoveIt2, which can be used for various manipulation tasks. Be sure to set a planner, such as TRRT, before planning and executing a motion plan. Low-Level Control ================= The low-level control for the H1 can be directly accessed via Unitree's provided examples in their `documentation `_. Running the provided **qre_h1** driver with the low-level commands from Unitree examples should work concurrently. SLAM Setup ========== .. note:: This section is currently under development. We are working diligently to provide you with comprehensive and detailed instructions for setting up SLAM with the H1 robot. We appreciate your patience and understanding during this process. Stay tuned for updates! .. To create a map for map-based navigation, the first step is to map the environment. .. .. figure:: figures/.png .. :width: 100% .. :align: center .. :alt: Move the robot slowly when building the map .. Move the robot slowly when building the map. .. Steps to Create a Map: .. 1. Launch the SLAM: .. .. code-block:: bash .. ros2 launch h1_navigation slam.launch.py .. 2. Begin mapping using the **teleop** at **0.2m/s** with the keyboard or the provided Logitech controller. Once you are satisfied with your map, export it by running the following commands: .. .. code-block:: bash .. cd /home/unitree/ros2_ws/src/h1_navigation/maps/ .. ros2 run nav2_map_server map_saver_cli -f map_ .. 3. If the map name is not **map_**, you need to rebuild so that the maps can be found: .. .. code-block:: bash .. colcon build --symlink-install .. 4. Then source the environment: .. .. code-block:: bash .. source /home/$USER/ros2_ws/install/setup.bash Odometric Navigation ==================== .. note:: This section is currently under development. We are committed to enhancing the documentation for odometric navigation with the H1 robot and will provide detailed guidance soon. Thank you for your patience and understanding as we work to improve your experience! .. To navigate without creating a map, you can launch the odometry navigation and give goals in RVIZ: .. .. code-block:: bash .. ros2 launch h1_navigation odom_navi.launch.py Map-Based Navigation ==================== .. note:: This section is currently under development. We are actively working on creating comprehensive instructions for map-based navigation with the H1 robot. Your patience is greatly appreciated as we strive to bring you the best resources possible! .. This mode will automatically use the map created and saved from SLAM, assuming it is named **map_**. If the map has a different name, you must update the parameters in **h1_navigation**. .. .. figure:: figures/.png .. :width: 100% .. :align: center .. :alt: Select the 2D Pose Estimate and drag to the corresponding location on the map. .. Select the **2D Pose Estimate** and drag to where the robot corresponds in the map. .. .. figure:: figures/.png .. :width: 100% .. :align: center .. :alt: The robot self-corrects its position when moving. .. Once the robot is in the estimated location, it should self-correct while moving. .. Steps to Launch Map Navigation: .. 1. Ensure the map is generated and available in the ROS package (after saving the map, perform **colcon build**): .. .. code-block:: bash .. ros2 launch h1_navigation map_navi.launch.py Drivers Launch ============== Launch the H1 ROS driver that communicates and publishes the state of the robot joints: .. code-block:: bash ros2 launch h1_bringup system.launch.py Intel Realsense D435i ===================== 1. The D435i is launched by default with the H1 bringup. To launch the Realsense D435i separately, execute: .. code-block:: bash ros2 launch h1_depth_camera realsense_d435i.launch.py 2. The launch file is configured to enable continuous depth stream information from the Realsense D435i without lag. To further change parameters, modify the configuration in: .. code-block:: bash h1_depth_camera/launch/realsense_d435i.launch.py +-------------------------------------------------------+------------------------------------------------------------+ | .. figure:: media/gifs/h1_d4351i_normal.gif | .. figure:: media/gifs/h1_d4351i_depth.gif | | :width: 100% | :width: 90% | | :align: center | :align: center | | :alt: Intel Realsense D435i Normal Output | :alt: Intel Realsense D435i Depth Output | | | | | Intel Realsense D435i Normal Output | Intel Realsense D435i Depth Output | +-------------------------------------------------------+------------------------------------------------------------+ Mid360 Lidar ============ 1. The Mid360 is launched by default with the H1 bringup. To activate the Mid360 Lidar, execute: .. code-block:: bash ros2 launch h1_livox system.launch.py .. figure:: media/gifs/mid360_output.gif :width: 100% :align: center :alt: Mid360 Lidar Output Visualization in RViz Mid360 Lidar Output Visualization in RViz MoveIt2 Launch ============== Launch MoveIt2 for robotic manipulation tasks: .. code-block:: bash ros2 launch h1_moveit system.launch.py Nvidia Installation =================== .. note:: This repository should already be available and built on the H1's Nvidia board if it has been configured by the MYBOTSHOP team. 1. Clone this repository into the H1's Nvidia board. 2. Run the bash install script. 3. Build the repository by executing the following command: .. code-block:: bash colcon build --symlink-install && source install/setup.bash 4. After building, remember to source the `install/setup.bash`. Ensure you add the source command to your workspace in the `.bashrc` file. Unitree SDK Installation (Host PC) ================================== .. note:: **Important:** This process is necessary to enable Unitree SDK's DDS topics to appear. Without these steps, only the MYBOTSHOP package ROS2 topics will be visible. You can skip this procedure if you do not need the Unitree topics. Part 1 ------ 1. Navigate to the **unitree_sdk2** folder inside the **thirdparty** directory and execute the installation script: .. code-block:: bash cd thirdparty/unitree_sdk2 sudo bash install.sh 2. Build the examples: .. code-block:: bash rm -rf build && mkdir build && cd build && cmake .. && make 3. You can now directly run high-level and low-level examples as explained in the Unitree H1 SDK documentation. Part 2 ------ **Requirements:** ROS2 Foxy on **Ubuntu 20.04**. 1. Install the necessary dependencies: .. code-block:: bash sudo apt install ros-$ROS_DISTRO-rmw-cyclonedds-cpp ros-$ROS_DISTRO-rosidl-generator-dds-idl -y 2. Unsource ROS Foxy in the terminal (i.e., by commenting out the sourcing command in the `.bashrc` file). 3. Build Cyclone DDS: .. code-block:: bash colcon build --packages-select cyclonedds 4. Install other dependencies by running the provided install script: .. code-block:: bash sudo chmod +x h1_install.bash && ./h1_install.bash 5. Source the environment: .. code-block:: bash source install/setup.bash source /opt/ros/foxy/setup.bash 6. Build the repository: .. code-block:: bash colcon build --symlink-install Network Setup ------------- 1. Connect to the **123** network using a static IP (No DHCP, as it disrupts the network). 2. Note down the network interface name (e.g., `eth0`). 3. Edit and source the `h1_bringup/config/setup.bash` file with the corrected network interface. For example: .. code-block:: bash #!/bin/bash echo "Setup Unitree ROS2 environment" source /opt/ros/foxy/setup.bash source $HOME/ros2_ws/install/setup.bash export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp export CYCLONEDDS_URI=' ' 4. Add the above to your `.bashrc` file for persistence. Verification ------------ 1. Check the available ROS2 topics: .. code-block:: bash ros2 topic list 2. Echo a specific topic (e.g., `/lowstate`): .. code-block:: bash ros2 topic echo /lowstate .. Installation (Host PC) .. ======================= .. .. note:: .. **Important:** The ROS2 topics should automatically appear under `ROS_DOMAIN_ID=10` with a default ROS2 setup. However, the H1 Unitree topics will not appear. If you require the Unitree topics, please follow the instructions below. .. This setup requires the installation of **ROS2 Foxy** on **Ubuntu 20.04**. This is highly recommended if you wish to view RVIZ on your own computer without latency. All the instructions provided here are to be performed on your own computer. .. First Time Setup .. ---------------- .. .. note:: .. Make sure the command `source /opt/ros/foxy/setup.bash` has not been activated. .. 1. Install dependencies located in the `qre_h1/src` directory: .. .. code-block:: .. ./h1_install.bash .. 2. Create a folder named **ros2_ws** in your home directory and clone the **foxy** branch of **qre_h1** into it. .. 3. Build Cyclone in the **ros2_ws** directory: .. .. code-block:: .. colcon build --packages-select cyclonedds .. 4. Source the workspace: .. .. code-block:: .. source install/setup.bash .. 5. Now source the ROS Foxy distribution: .. .. code-block:: .. source /opt/ros/foxy/setup.bash .. 6. Next, build the repository twice: .. .. code-block:: .. colcon build --symlink-install .. 7. Source the built ROS workspace: .. .. code-block:: .. source /home/$USER/ros2_ws/install/setup.bash .. 8. Connect to the **123** network with a static IP as described in the Network section :ref:`sec:network`, and then note down the network interface name. .. 9. Edit and source `h1_bringup/config/setup.bash` with the corrected network interface (e.g., **enp92s0**). .. 10. Then source the special configuration for the H1: .. .. code-block:: .. source /home/$USER/ros2_ws/src/h1_bringup/setup.bash .. 11. Now, if you are connected via LAN to the H1, running `ros2 topic list` should show the topics from the H1. .. After First Time Setup .. ---------------------- .. 1. Once the first-time setup is completed, the next time simply run: .. .. code-block:: .. source /opt/ros/foxy/setup.bash .. source /home/$USER/ros2_ws/src/h1_bringup/setup.bash .. 2. You can now communicate with ROS2 features on the H1. To test it, launch: .. .. code-block:: .. ros2 launch h1_viz view_robot.launch.py .. H1 Network Table .. ---------------- .. Below is the list of IP addresses assigned to various components of the H1 robot: .. - **192.168.123.161** -> H1 MCU .. - **192.168.123.162** -> H1 Auxiliary PC 2 .. - **192.168.123.163** -> H1 Auxiliary PC 3 .. - **192.168.123.120** -> Mid360 Lidar .. **Important:** Do not set your device's IP to any of the above H1 IPs to avoid conflicts. .. H1 SSH Access .. ------------- .. To SSH into H1 Auxiliary PC 3, use the following credentials: .. - **SSH ID:** `unitree@192.168.123.163` .. - **Password:** `Unitree0408` .. You can use the following command to SSH: .. .. code-block:: bash .. ssh unitree@192.168.123.163 .. H1 Internet Setup .. ----------------- .. To enable LAN via the ethernet cable, follow these steps. We recommend using a USB WiFi stick to get internet access on the H1 robot. .. .. code-block:: bash .. sudo ip link set eth0 down && sudo ip link set eth0 up .. sudo dhclient eth0 .. H1 Ethernet Connection .. ----------------------- .. To connect the H1 robot to the Ethernet: .. 1. Power on the robot. .. 2. Connect the LAN cable to the Ethernet port (Top Most port for the demo unit). .. H1 Installation (Onboard PC2) - First Time Setup .. ------------------------------------------------ .. For the first-time setup of H1 on **Onboard PC2**, follow these steps: .. 1. **Update time and date** on H1 PC2 using the following command: .. .. code-block:: bash .. sudo date -s "$(wget --method=HEAD -qSO- --max-redirect=0 google.com 2>&1 | sed -n 's/^ *Date: *//p')" .. 2. **Clone the repository** and copy it over to the H1 PC2, then run the installer script: .. .. code-block:: bash .. cd && cd ros2_ws/src && ./h1_install.bash .. 3. **Build the Livox SDK** (Mid360): .. .. code-block:: bash .. cd && cd ros2_ws/src/third_party/sensors/Livox-SDK2/ .. rm -rf build && mkdir build && cd build && cmake .. && make -j && sudo make install .. 4. In the third-party directory, go to `unitree_sdk2` and execute the install script: .. .. code-block:: bash .. sudo bash install.sh .. 5. **Build the examples** in `unitree_sdk2`: .. .. code-block:: bash .. rm -rf build && mkdir build && cd build && cmake .. && make .. 6. **Copy over to `.bashrc`:** .. .. code-block:: bash .. source /home/unitree/ros2_ws/install/setup.bash .. 7. **Build the ROS2 workspace:** .. .. code-block:: bash .. cd && cd ros2_ws && colcon build --symlink-install && source install/setup.bash .. H1 Livox Setup (First Time) .. --------------------------- .. If you need to set up the Livox Mid360 for the first time or after a reset, follow these steps: .. 1. Temporarily set up the IP for the Livox sensor: .. .. code-block:: bash .. sudo ip addr flush dev eth0 .. sudo ip addr add 192.168.1.5/24 dev eth0 .. sudo ip link set eth0 up .. H1 ROS2 Documentation .. ===================== .. Driver Configuration .. -------------------- .. To configure the H1 driver, edit the configuration file located at: .. h1_base/config/h1_base.yaml .. Modify the parameters as required for your setup. .. Starting Drivers .. ---------------- .. To start the H1 ROS driver, use the following command: .. .. code-block:: bash .. ros2 launch h1_bringup system.launch.py .. To launch the H1 RViz visualization, run: .. .. code-block:: bash .. ros2 launch h1_viz view_robot.launch.py .. Operation .. --------- .. Unitree is currently developing ROS2 examples for the H1 robot. As a temporary workaround to operate the system, use the following command: .. .. code-block:: bash .. ros2 launch h1_base control.launch.py .. Teleoperation .. -------------- .. To teleoperate the H1 robot, set the ROS domain ID and run the teleop_twist_keyboard node: .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 run teleop_twist_keyboard teleop_twist_keyboard .. Legs Modes Selection .. -------------------- .. To switch between different modes for the H1 robot, use the following ROS service calls: .. - **Switch to movement mode or back to standing mode:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/modes h1_srvs/srv/H1Modes '{"request_data": stand_switch}' .. - **Damp all motors:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/modes h1_srvs/srv/H1Modes '{"request_data": damp}' .. - **Increase foot height:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/modes h1_srvs/srv/H1Modes '{"request_data": increase_swing_height}' .. - **Decrease foot height:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/modes h1_srvs/srv/H1Modes '{"request_data": decrease_swing_height}' .. - **Switch to ready mode:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/modes h1_srvs/srv/H1Modes '{"request_data": enable_ctrl}' .. For more detailed information, refer to the Unitree documentation. .. Arm Modes Selection .. -------------------- .. To calibrate the arms (Mandatory): .. **Warning:** Be careful, the robot will perform a T-Pose with the arms. .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/arm_modes h1_srvs/srv/H1Modes '{"request_data": arms_calibrate}' .. - **Put the arm in T-Pose:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/arm_modes h1_srvs/srv/H1Modes '{"request_data": arms_straight}' .. - **Put the arm in down-Pose:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/arm_modes h1_srvs/srv/H1Modes '{"request_data": arms_down}' .. - **Stop arm control:** .. .. code-block:: bash .. ROS_DOMAIN_ID=10 ros2 service call /h1/arm_modes h1_srvs/srv/H1Modes '{"request_data": arms_stop}' .. Depth Camera Realsense D435i .. ----------------------------- .. To test the native driver, run: .. .. code-block:: bash .. ros2 launch realsense2_camera rs_launch.py depth_module.depth_profile:=1280x720x30 pointcloud.enable:=true .. Simultaneous Localization and Mapping .. -------------------------------------- .. Ensure that `h1_bringup` is running, then launch SLAM: .. .. code-block:: bash .. ros2 launch h1_navigation slam.launch.py .. To begin mapping using the teleop at 2m/s with the keyboard, run: .. .. code-block:: bash .. ros2 run nav2_map_server map_saver_cli -f map_ .. To rebuild so that it can be found, use: .. .. code-block:: bash .. colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release .. Odometric Navigation .. --------------------- .. To launch odometric navigation, run: .. .. code-block:: bash .. ros2 launch h1_navigation odom_navi.launch.py .. Map Navigation .. -------------- .. Ensure that a map is generated and available in the ROS package (i.e., after saving the map, place it and perform `colcon build`). Then, launch map navigation: .. .. code-block:: bash .. ros2 launch h1_navigation map_navi.launch.py .. H1 Isaac Sim .. ------------ .. **Note:** Please refer to the Isaac Sim Guide for detailed instructions. .. H1 Installation Unitree (Host PC) .. ================================= .. **Important:** .. This procedure is necessary to enable Unitree's SDK DDS topics to appear. If you do not require Unitree topics, you may skip these steps as only the MYBOTSHOP package ROS2 topics will display. .. Part-1 .. ------- .. 1. Navigate to the `unitree_sdk2` directory within `thirdparty` and execute the installation script: .. .. code-block:: bash .. sudo bash install.sh .. 2. Build the examples: .. .. code-block:: bash .. rm -rf build && mkdir build && cd build && cmake .. && make .. You can now run high-level and low-level examples as explained in the Unitree H1 SDK documentation. .. Part-2 .. ------- .. 1. **Requires ROS2 Foxy on Ubuntu 20.04** .. 2. Install dependencies: .. .. code-block:: bash .. sudo apt install ros-$ROS_DISTRO-rmw-cyclonedds-cpp ros-$ROS_DISTRO-rosidl-generator-dds-idl -y .. 3. Unsource ROS2 Foxy in the terminal (e.g., by commenting it out in `.bashrc`): .. .. code-block:: bash .. colcon build --packages-select cyclonedds .. 4. Install additional dependencies using the provided script: .. .. code-block:: bash .. sudo chmod +x h1_install.bash && ./h1_install.bash .. 5. Source the setup scripts: .. .. code-block:: bash .. source install/setup.bash .. source /opt/ros/foxy/setup.bash .. 6. Build the workspace with symbolic links: .. .. code-block:: bash .. colcon build --symlink-install .. 7. Connect to the `123` network with a static IP (avoid DHCP as it disrupts the network). Note the network interface. .. 8. Edit and source `h1_bringup/config/setup.bash` with the correct network interface. Example configuration: .. .. code-block:: bash .. #!/bin/bash .. echo "Setup Unitree ROS2 environment" .. source /opt/ros/foxy/setup.bash .. source $HOME/ros2_ws/install/setup.bash .. export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp .. export CYCLONEDDS_URI=' .. .. ' .. 9. Add the following to `.bashrc` for automatic setup: .. .. code-block:: bash .. export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp .. export CYCLONEDDS_URI=' .. .. ' .. Verification .. ------------- .. 1. Check ROS2 topics: .. .. code-block:: bash .. ros2 topic list .. 2. Echo a specific topic: .. .. code-block:: bash .. ros2 topic echo /lowstate .. Miscellaneous .. -------------- .. 1. Sync host computer and Unitree computer: .. .. code-block:: bash .. rsync -avP -t --delete -e ssh src unitree@192.168.123.162://home/unitree/ros2_ws .. 2. Quick build base: .. .. code-block:: bash .. cd && cd ros2_ws && colcon build --symlink-install --packages-select h1_base && source install/setup.bash .. 3. Steamdeck build (build only required packages for Steamdeck): .. .. code-block:: bash .. colcon build --symlink-install --packages-select h1_srvs h1_steamdeck h1_description h1_control h1_viz h1_navigation h1_depth_camera h1_bringup && source install/setup.bash .. 4. Enable Unitree H1 to publish topics via WiFi: .. Add the following function to `.bashrc`: .. .. code-block:: bash .. enter_wifi_mode_h1(){ .. source /home/unitree/slam_config/cyclone_go2_B2_ws/install/setup.bash .. export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp .. export CYCLONEDDS_URI=/home/unitree/ros2_ws/src/h1_steamdeck/config/cyclone_wifi.xml .. export LD_LIBRARY_PATH=/usr/local/lib:$LD_LIBRARY_PATH .. source /opt/ros/foxy/setup.bash .. # <<< fishros initialize <<< .. source /home/unitree/ros2_ws/install/setup.bash .. } .. Add the following aliases to `.bashrc`: .. .. code-block:: bash .. alias setdate='sudo date -s "$(wget --method=HEAD -qSO- --max-redirect=0 google.com 2>&1 | sed -n "s/^ *Date: *//p")"' .. alias h1b='cd && cd ros2_ws && colcon build --symlink-install --packages-select h1_base && source install/setup.bash && cd' .. alias ros2_wifi=enter_wifi_mode_h1 .. Quick-Start .. =========== .. Unboxing .. -------- .. - The H1 will be delivered within a secondary cardboard box, as illustrated in the images provided below. .. .. image:: media/figures/secondary.jpg .. :width: 50% .. - Within this secondary box, you will discover the primary white box featuring the robot's image and a description of its functionalities. .. .. image:: media/figures/primary3.jpg .. :width: 50% .. .. image:: media/figures/primary1.jpg .. :width: 50% .. - Inside the primary box, there is a practical gray-colored travel trolley bag designed for convenient day-to-day transportation of the robot. .. .. image:: media/figures/troly1.jpg .. :width: 50% .. .. image:: media/figures/troly2.jpg .. :width: 50% .. - The final product from the box will look as shown above. .. You can access the unboxing video by following the provided link below. .. - `H1 Unboxing `__ .. ROS2 .. ---- .. (Coming Soon) .. Quadruped Robotics Europe is a young, but fast growing startup in the field of legged robotics. In this documentation, the software overview of H1 robot is shown. The software is currently under development. At the moment simples ros drivers are available for the robot along with simulation are available in Gazebo. As several variants of H1 are provided with different hardware versions, the following video demonstrates operation of the software development kit `H1 Operation <>`__ for the H1. Quick-Start Teleop ?? ------------------ A pre-configured H1 can start its navigation via the following commands: .. attention:: Note that the current navigation utilizes unitrees innate controller and it does not currently perform terrain adaptibility. For that low-level-mode is required which is under development. 1. Launch High-level driver .. code-block:: bash sudo su source catkin_ws/devel/setup.bash roslaunch qre_ros high_level_mode.launch 2. Launch teleop .. code-block:: bash rosrun teleop_twist_keyboard teleop_twist_keyboard.py Quick-Start Autonomous Navigation ?? --------------------------------- A pre-configured H1 can start its navigation via the following commands: .. attention:: Note that the current navigation utilizes unitrees innate controller and it does not currently perform terrain adaptibility. For that low-level-mode is required which is under development. 1. Launch High-level driver .. code-block:: bash sudo su source catkin_ws/devel/setup.bash roslaunch qre_ros high_level_mode.launch 2. Launch qre driver .. code-block:: bash roslaunch qre_driver qre_base_driver.launch This launches the robot state publisher, joint state publisher, IMU publisher, and Odom publisher. Note: The odom requires a visual odometry topic to work which we generally provide with the ZED2 camera. Incase you need to perform odometry calculation with another camera `VINS_Fusion `__ is a good software to use. 3. Launch ouster driver .. code-block:: bash roslaunch mbs_ouster ouster.launch 4. Launch navigation driver .. code-block:: bash roslaunch mbs_navigation odom_navigation.launch Now it is possible to give the robot navigation goals via movebase. 5. Launch visualizer .. code-block:: bash roslaunch qre_viz viz.launch You can now add point clouds and the raw_rgb_image to view the streamed data. Robot Setup ----------- To start-up the robot the following instructional video should be used which details the opening and use of the H1 as well as operation: * `Starting the robot`_ * `Robot operation`_ * `Paw replacement`_ * `R\&D (outdated)`_ * `Unitree App`_ * `Operation with app`_ .. note:: The list above is hyerlinked. Simply click on the text to get redirected to the website. Network- Setup?? -------------- The H1 has multiple networks and vary slightly, the following table shows the networks .. table:: H1 network devices ================ ================ ======== Device Network Address Password ================ ================ ======== H1-pi 192.168.123.161 123 H1-nvidia(head) 192.168.123.13 123 H1-nvidia(body) 192.168.123.13 123 H1-nvidia(body) 192.168.123.13 123 H1-MCU 192.168.123.10 N/A Ouster 192.168.123.51 N/A ================ ================ ======== Hotspot?? ~~~~~~~ H1 has its own native hot-spot to which users can connect as well as an Ethernet port to access its on-board computers. Moreover, H1 has the network address range of ``192.168.123.*``. The Mobile app allows you to configure the SSID and Password for H1's hotspot Wi-Fi network during the initial setup. Once connected to the WiFi network, one can access H1's Nvidia ip address ``192.168.131.161`` as well as the Raspberry Pi's ip address ``192.168.123.12``. To achieve this enter the command terminal of the computer that has connected to the WiFi hot-spot of the robot and enter the following: - To connect with the Nvidia's on-board PC: .. code-block:: bash ssh -X unitree@192.168.123.161 123 - To connect with the Raspberry Pi's on-board PC: .. code-block:: bash ssh -X unitree@192.168.123.12 123 Mobile-App ?? ~~~~~~~~~~ - Install the unitree app for H1 from `Unitree App`_ - Connect to the H1's hotspot and select the vision system to see the H1's camera stream Direct Power-Supply ?? ~~~~~~~~~~~~~~~~~~~ 1. Remove the battery from the H1. 2. Ensure the H1 is placed on the ground with all four paws as well as knee joints touching the ground. - It is advised to place robot on some carpet or similar compressible surface to prevent damage to the joints. 3. Connect the cable to the connection ports on the H1’s back. - The H1 requires 24V with around 3A of current. At startup it may take up to 20A of current. - Be vigiliant and make sure the *XT30* male pins are in the correct orientation when plugging in. The procedure described below is only for development purposes. It turns on the robot without battery inside from external power supply. The power supply should atleast be able to provide **24V/3A**. .. _Unitree App: https://m.unitree.com/app .. _Starting the robot: https://www.youtube.com/watch?v=Xz6d1gaBCTk .. _Robot operation: https://youtu.be/2vTFCTJiOH0 .. _Paw replacement: https://www.youtube.com/watch?v=iOq0IFXOSaE .. _Operation with app: https://www.youtube.com/watch?v=Kj7GrVpBWWc .. _R\&D (outdated): https://github.com/unitreerobotics Calibration ?? ============ Robot Drift ?? ----------- 1. Turn on the robot and the remote.Once the robot is fully booted and stands up, press start 2. While the robot is trortting press the left or right arrow keys opposite of the H1 drift on the controller keypad 3. Continue pressing the keys until drift stops and press b to save (this has to be done before the robot trotting stops) IMU Calibration ?? ---------------- IMU can be calibrated by using the following `file `__. - Download `document(EXE) #1 `__ - Download `document(EXE) #2 `__ Leg Calibration ?? ---------------- Some H1 have different firmware. For most of the H1's follow until step 2, and then continue from the calibration video. 1. Turn on the robot dog, L2+B makes the robot dog lie down. 2. Press L2+B twice to make the robot dog enter the undamped mode .. important:: Twisting the leg joints of the robot dog will not feel damping at this time Follow the video guide for the rest of the `video guide `__, as the procedure is the same. Remote Calibration ?? ------------------ - Hold the remote control but do not touch the joystick. - Press the remote control buttons F1 and F3 and release them at the same time. At this time, the remote control will emit a continuous ``drip ~ drip ~`` sound (1 time / second) to indicate that it has entered the calibration mode. - After entering the calibration mode, move the left and right joysticks to full rudder and rotate it several times until the ``drip ~ drip ~`` sound stops, and the calibration is ready. - Press F3 once to make the calibration take effect and complete the calibration. .. note:: Please do not touch the joystick before calibrating, only enter the calibration mode to move the joystick. After calibration, you can view the status of the joystick after calibration through APP. (reference Page: 33 of the user manual) Robot Falling Over ------------------ - Replace the robots foot paws.