Pre-requisites

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 G1 robot, including network configurations, SSH access, internet setup, software installation and various operational controls. Follow the steps below carefully to ensure proper operation.

Network Interface

Static Network Connection

For first-time setup, you need to connect via LAN cable to configure the robot’s network.

On your PC (Ubuntu):

  1. Navigate to Settings → Network.

  2. Click on the “+” icon to create a new connection.

  3. In IPv4 Settings, set the connection method to Manual.

  4. Enter the following details:

    • Address IP: 192.168.123.51

    • Netmask: 24

  5. Save and restart your network.

After a successful connection, check the host PC’s local IP:

ifconfig

Ping the robot to verify connectivity:

ping 192.168.123.164

Access the robot via SSH:

ssh -X unitree@192.168.123.164

Default password:

123

Network Table

IP Address

Device

Username

Password

192.168.123.161

G1 MCU

x

x

192.168.123.164

G1 Auxiliary PC 2

unitree

123

192.168.123.164:9000

G1 Webserver MBS

x

mybotshop

192.168.123.120

Mid360 Lidar

x

x

Note

Do not set your PC IP as any of the G1 IP addresses listed below.

Enable Internet LAN

This enables LAN via the ethernet cable. Ensure the cable is connected to a router with internet access.

sudo ip link set eth1 down && sudo ip link set eth1 up
sudo dhclient eth1
sudo date -s "$(wget --method=HEAD -qSO- --max-redirect=0 google.com 2>&1 | sed -n 's/^ *Date: *//p')"
ping google.com

Enable Internet WiFi (Recommended)

You can attach a hub and WiFi via a hub. A link to a cost-effective hub and WiFi stick is provided in Enhancements.

sudo ip link set eth0 down && sudo ip link set eth0 up
sudo dhclient eth0

Autostart

All ROS2 drivers for the G1 developed by MYBOTSHOP operate with the environment variable ROS_DOMAIN_ID=10.

To start the custom Mybotshop ROS2 drivers for the G1, 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.

ros2 launch g1_bringup system.launch.py

This command starts the driver for operating the G1 in high-level mode for the legs and arms.

Important

The arms will initialize and move so that the forearms are facing forward.

The G1 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

Webserver

G1 Webserver

This module should come pre-installed for heavy integration projects. It should be accessible directly at http://192.168.123.164:9000/ or the WiFi ip to which the robot is connected. The G1 webserver can be configured via the config file in g1_webserver ros2 package located in /opt/mybotshop/src/mybotshop/g1_webserver/config/robot_webserver.yaml

Login

_images/web_login.png

Dashboard

  • Enable the G1 ROS2 Services

  • Disable the G1 ROS2 Services

  • Record System G1 logs

_images/web_dashboard.png

System

  • View G1 external PC system status.

  • The battery only runs if the ROS2 drivers are enabled from the dashboard

_images/web_system.png

Console

  • Movement of the Unitree G1

  • Switch between Gaits

  • Adapatable to new ros2 services

  • Record ROS2 bags

  • Access G1 external speaker if available

  • The console only works if the ROS2 drivers are enabled from the dashboard


_images/web_console.png

Remote Desktop

  • On-board screen of the Unitree G1’s computer

_images/web_vnc.png

Navi Indoor

  • Disabled

_images/web_nav_indoor.png

Navi Outdoor

  • Disabled

Packages

ROS2 Modules for G1

Note

Please ensure that the arms are straight down when you power on the robot. If the orientation is different, it will affect the ROS2 control operation.

The ROS2 modules start drivers for operating G1 in high-level mode for legs and arms.

Important

During initialization, the arms will move such that the forearms will face forward.

Launch G1 ROS2 Driver

The driver includes the following modules:

  • 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


These modules can also be viewed, activated, or deactivated from the Webserver.

ros2 launch g1_platform highlevel_ros.launch.py

Core Launch Files

These launch files can also be managed from the webserver. Ensure the Webserver is running. Follow the installation procedure first.

ros2 launch g1_platform highlevel_ros.launch.py
ros2 launch g1_platform domain_bridge.launch.py
ros2 launch g1_platform state_publisher.launch.py
ros2 launch g1_webserver webserver.launch.py
ros2 launch g1_control twistmux.launch.py
ros2 launch g1_lidar livox_mid360.launch.py
ros2 launch g1_platform audio.launch.py
ros2 launch g1_platform led.launch.py
ros2 launch g1_platform videostream.launch.py

Arms 7Dof Core Launch Files

ros2 launch g1_description g1_29_description.launch.py
ros2 launch g1_platform arm_7dof.launch.py

Arms 5Dof Core Launch Files

ros2 launch g1_description g1_23_description.launch.py
ros2 launch g1_platform arm_5dof.launch.py

G1 Modes Selection

Posture & State Commands

The table below lists commands for controlling the robot’s posture and state:

Command

Description

damp

Set all motors to damping mode.

start

Start locomotion control.

squat

Transition to squat posture.

sit

Sit down.

stand_up

Stand up from sitting/squatting.

zero_torque

Disable torque on all motors.

stop_move

Stop all motion immediately.

high_stand

Stand at high position.

low_stand

Stand at low position.

balance_stand

Stand with balance mode active.

shake_hand

Perform handshake sequence (auto-start and stop).

wave_hand

Perform wave motion.

wave_hand_with_turn

Wave hand and turn simultaneously.

Setter Commands (Change Robot State)

Command

Parameters

set_fsm_id=<id>

Integer FSM ID to switch to.

set_balance_mode=<0/1>

Enable (1) or disable (0) balance mode.

set_swing_height=<value>

Set swing height in meters.

set_stand_height=<value>

Set stand height in meters.

set_velocity=”vx vy ω [duration]”

Set velocity (m/s, m/s, rad/s, [duration in s]).

move=”vx vy ω”

Command motion without duration.

set_task_id=<id>

Set active task ID.

set_speed_mode=<mode>

Change locomotion speed mode.

Getter Commands (Query Current Robot State)

Command

Returns

get_fsm_id

Current finite state machine ID.

get_fsm_mode

Current FSM mode.

get_balance_mode

Current balance mode (0/1).

get_swing_height

Current swing foot height.

get_stand_height

Current standing height.

get_phase

Current gait phase vector.

Toggle Commands

Command

Parameters

Description

continous_gait=<true/false>

bool

Enable or disable continuous gait mode.

switch_move_mode=<true/false>

bool

Switch between movement mode and standing mode.

G1 Mode Examples

Start the robot

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware_modes g1_interface/srv/G1Modes \
'{"request_data": "start"}'

Shake hand

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware_modes g1_interface/srv/G1Modes \
'{"request_data": "shake_hand"}'

Wave hand

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware_modes g1_interface/srv/G1Modes \
'{"request_data": "wave_hand_with_turn"}'

Set swing height

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware_modes g1_interface/srv/G1Modes \
'{"request_data": "set_swing_height=0.12"}'

Move forward

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware_modes g1_interface/srv/G1Modes \
'{"request_data": "set_velocity=0.3 0.0 0.0 2.0"}'

Query current FSM mode

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware_modes g1_interface/srv/G1Modes \
'{"request_data": "get_fsm_mode"}'

Enable continuous gait

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware_modes g1_interface/srv/G1Modes \
'{"request_data": "continous_gait=true"}'

G1 LED Selection

Set color

ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'color=green'}"
ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'color=red'}"
ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'color=white'}"
ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'color=blue'}"

Set color with hex and brightness

ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'color=#00a0a0;brightness=60'}"

Set color with RGB

ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'color=rgb(128,32,200)'}"

Query LED state

ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'get_brightness'}"
ros2 service call /g1_unit_001/hardware/led g1_interface/srv/G1Modes "{request_data: 'get_color'}"

G1 Audio Selection

Set volume

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware/audio g1_interface/srv/G1Modes "{request_data: 'volume=80'}"

Speak English

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware/audio g1_interface/srv/G1Modes "{request_data: 'speak=Hello from MY BOT SHOP'}"

Volume + Text

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware/audio g1_interface/srv/G1Modes "{request_data: 'volume=100;speak= Hello from my bot shop. My name is Danny'}"

Get current volume

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware/audio g1_interface/srv/G1Modes "{request_data: 'get_volume'}"

Self Intro

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware/audio g1_interface/srv/G1Modes "{request_data: 'volume=100;speak= Hello from my bot shop. I am Danny, a compact humanoid robot for research and education. My height is 1.32 meters, and my weight is 35 kg. I walk up to 2 meters per second, climb stairs, and keep balance. Hehehe climbing stairs not really. My base model has 23 degrees of freedom where as my educational + version has 43 degrees of freedom. I have 3D liDAR specifically Livox Mid360 and depth camera Intel RealSense D435i. Battery lasts about 2 hours +'}"

Note

More info on these commands is available in the Unitree documentation.

Robot Description

The G1 robot description package is named g1_description. It contains the URDF and mesh files necessary to visualize and simulate the G1 robot in various ROS2 tools.

Twist Mux

The twist mux package for the G1 is named g1_control. It manages multiple velocity command inputs and prioritizes them to ensure smooth and safe robot operation.

EKF Localization

The Extended Kalman Filter (EKF) localization package for the G1 is named g1_control. It fuses sensor data to provide accurate and reliable robot pose estimates.

Teleoperation

Command Line Interface

This requires installation of the ROS2 modules on G1. If not installed, please follow the G1 Auxiliary PC Installation guide.

ROS_DOMAIN_ID=10 ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=/$G1_NS/hardware/cmd_vel

Steamdeck

  1. Please follow the instructions carefully in here to start the G1 Steamdeck.

  2. Connect to the custom router of the G1, it may take a few minutes on startup of the robot.

  • The IP of the steamdeck is 192.168.123.150

  • The IP of the router is 192.168.123.100

  • The IP of the Unitree G1 is 192.168.123.18

  1. Once the joystick is opened hold L1 and use the left and right joystick to move the robot.

  2. The web browser will automatically open and take you to https://192.168.123.18:9000.

  3. The drivers on G1 are off by default. You can click on restart all to start all ROS2 services enabling control via the steamdeck+ros2.

Visualization

RViz2

You can view the G1’s current state by entering the following command in one of the SSH sessions:

ros2 launch g1_viz view_robot.launch.py

Manipulation

G1 Arm ROS2 Control

Start the arms (Mandatory)

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware/control/arm_dof7/start std_srvs/srv/Trigger {}

Stop the arms (Mandatory)

ROS_DOMAIN_ID=10 ros2 service call /g1_unit_001/hardware/control/arm_dof7/stop std_srvs/srv/Trigger {}

Move dual arms

Will wave on spot — clear the area around the G1.

ROS_DOMAIN_ID=10 ros2 action send_goal /g1_unit_001/dual_arm/follow_joint_trajectory control_msgs/action/FollowJointTrajectory "{
  trajectory: {
    joint_names: [
      \"left_shoulder_pitch\",\"left_shoulder_roll\",\"left_shoulder_yaw\",
      \"left_elbow\",\"left_wrist_roll\",\"left_wrist_pitch\",\"left_wrist_yaw\",
      \"right_shoulder_pitch\",\"right_shoulder_roll\",\"right_shoulder_yaw\",
      \"right_elbow\",\"right_wrist_roll\",\"right_wrist_pitch\",\"right_wrist_yaw\"
    ],
    points: [
      { positions: [0.0, 0.2, 0.0, 1.57, 0.0, 0.0, 0.0,   0.0, -0.2, 0.0, 1.57, 0.0, 0.0, 0.0],
        time_from_start: {sec: 2, nanosec: 0} },
      { positions: [0.0, 1.57, 1.57, -1.57, 0.0, 0.0, 0.0,   0.0, -1.57, -1.57, -1.57, 0.0, 0.0, 0.0],
        time_from_start: {sec: 4} },
      { positions: [0.0, 1.57, 1.57, -1.0, 0.0, 0.0, 0.0,   0.0, -1.57, -1.57, -1.0, 0.0, 0.0, 0.0],
        time_from_start: {sec: 6} },
      { positions: [0.0, 1.57, 1.57, -1.57, 0.0, 0.0, 0.0,   0.0, -1.57, -1.57, -1.57, 0.0, 0.0, 0.0],
        time_from_start: {sec: 8} },
      { positions: [0.0, 1.57, 1.57, -1.0, 0.0, 0.0, 0.0,   0.0, -1.57, -1.57, -1.0, 0.0, 0.0, 0.0],
        time_from_start: {sec: 10} },
      { positions: [0.0, 1.57, 1.57, -1.57, 0.0, 0.0, 0.0,   0.0, -1.57, -1.57, -1.57, 0.0, 0.0, 0.0],
        time_from_start: {sec: 12} },
      { positions: [0.0, 1.57, 1.57, -1.0, 0.0, 0.0, 0.0,   0.0, -1.57, -1.57, -1.0, 0.0, 0.0, 0.0],
        time_from_start: {sec: 14} },
      { positions: [0.0, 0.2, 0.0, 1.57, 0.0, 0.0, 0.0,   0.0, -0.2, 0.0, 1.57, 0.0, 0.0, 0.0],
        time_from_start: {sec: 16, nanosec: 0} }
    ]
  }
}"

Move left arm

ROS_DOMAIN_ID=10 ros2 action send_goal /g1_unit_001/left_arm/follow_joint_trajectory \
  control_msgs/action/FollowJointTrajectory \
  "{trajectory: {
      joint_names: [
        left_shoulder_pitch, left_shoulder_roll, left_shoulder_yaw,
        left_elbow, left_wrist_roll, left_wrist_pitch, left_wrist_yaw
      ],
      points: [
        {positions: [0.0, 0.2, 0.0, 1.57, 0.0, 0.0, 0.0],
         time_from_start: {sec: 2, nanosec: 0} }
      ]}}"

Move right arm

ROS_DOMAIN_ID=10 ros2 action send_goal /g1_unit_001/right_arm/follow_joint_trajectory \
  control_msgs/action/FollowJointTrajectory \
  "{trajectory: {
      joint_names: [
        right_shoulder_pitch, right_shoulder_roll, right_shoulder_yaw,
        right_elbow, right_wrist_roll, right_wrist_pitch, right_wrist_yaw
      ],
      points: [
        {positions: [0.0, -0.2, 0.0, 1.57, 0.0, 0.0, 0.0],
         time_from_start: {sec: 2, nanosec: 0}}
      ]}}"

Sensors

Depth Cameras

Intel Realsense D435i

  • The D435i is launched by default with the G1 bringup. To launch the Realsense D435i separately, execute:

    ros2 launch g1_depth_camera realsense_d435i.launch.py
    
  • Test the native driver via:

ros2 launch realsense2_camera rs_launch.py depth_module.depth_profile:=1280x720x30 pointcloud.enable:=true

Lidars

Livox Mid360

  • The Mid360 is launched by default with the G1 bringup. To activate the Mid360 Lidar, execute:

    ros2 launch g1_livox system.launch.py
    

Simulation

Gazebo

Work in progress: Gazebo simulation for G1 is under development and will be available soon.

Isaac Sim

Available in Isaac Lab directly.

Debugging

Debugging Tips

When running RQt GUI with multiple robots in the same network, it’s important to set a unique ROS_DOMAIN_ID for each robot to avoid communication conflicts. You can do this by exporting the ROS_DOMAIN_ID environment variable before launching RQt GUI. For example, to set the domain ID to 10, use the following command:

ROS_DOMAIN_ID=10 ros2 run rqt_gui rqt_gui --ros-args --remap tf:=/$g1_ns/tf --ros-args --remap tf_static:=/$g1_ns/tf_static

This command ensures that RQt GUI communicates with the robot assigned to domain ID 10, preventing interference from other robots on the network.

Dynamic Reconfigure

To adjust parameters on-the-fly using dynamic reconfigure, you can use the following command:

ROS_DOMAIN_ID=10 ros2 run rqt_reconfigure rqt_reconfigure --ros-args --remap tf:=/$g1_ns/tf --ros-args --remap tf_static:=/$g1_ns/tf_static

TF Tree

To visualize the TF tree of the G1 robot, you can use the following command:

ROS_DOMAIN_ID=10 ros2 run rqt_tf_tree rqt_tf_tree --force-discover --ros-args --remap tf:=/$g1_ns/tf --ros-args --remap tf_static:=/$g1_ns/tf_static
ROS_DOMAIN_ID=10 ros2 run tf2_tools view_frames.py --force-discover --ros-args --remap tf:=/$g1_ns/tf --ros-args --remap tf_static:=/$g1_ns/tf_static

Video stream

To view the video stream from the G1’s camera, you can use the following command:

gst-launch-1.0 udpsrc address=230.1.1.1 port=1720 multicast-iface=eth0 ! \
      application/x-rtp, media=video, encoding-name=H264 ! \
      rtph264depay ! queue max-size-buffers=1 ! h264parse ! queue ! avdec_h264 ! \
      videoconvert ! autovideosink

Miscellanious

Computer - Robot Synchronization

rsync -avP -t --delete -e ssh src unitree@192.168.123.164://opt/mybotshop

Low-Level Control

The low-level control for the G1 can be directly accessed via Unitree’s provided examples in their documentation. Running the provided qre_g1 driver with the low-level commands from Unitree examples should work concurrently.

Installation

Installation Robot

Note

This repository should already be available and built on the G1’s Nvidia board if it has been configured by the MYBOTSHOP team.

  1. Clone this repository into the G1’s Nvidia board.

  2. Run the bash install script.

  3. Build the repository by executing the following command:

    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.

Installation External

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:

    cd thirdparty/unitree_sdk2
    sudo bash install.sh
    
  2. Build the examples:

    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 G1 SDK documentation.

Part 2

Requirements: ROS2 Foxy on Ubuntu 20.04.

  1. Install the necessary dependencies:

    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:

    colcon build --packages-select cyclonedds
    
  4. Install other dependencies by running the provided install script:

    sudo chmod +x g1_install.bash && ./g1_install.bash
    
  5. Source the environment:

    source install/setup.bash
    source /opt/ros/foxy/setup.bash
    
  6. Build the repository:

    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 g1_bringup/config/setup.bash file with the corrected network interface. For example:

    #!/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='<CycloneDDS><Domain><General><Interfaces>
                               <NetworkInterface name="eth0" priority="default" multicast="default" />
                            </Interfaces></General></Domain></CycloneDDS>'
    
  4. Add the above to your .bashrc file for persistence.

Verification

  1. Check the available ROS2 topics:

    ros2 topic list
    
  2. Echo a specific topic (e.g., /lowstate):

    ros2 topic echo /lowstate