--- id: getting-started title: "Getting Started Guide" status: established source_sections: "reference/sources/community-weston-robot-guide.md, reference/sources/community-robonomics-experience.md, reference/sources/community-robostore-specs.md, reference/sources/official-quick-start.md" related_topics: [deployment-operations, sdk-programming, networking-comms, safety-limits, simulation, hardware-specs] key_equations: [] key_terms: [unitree_sdk2, cyclone_dds, locomotion_computer, development_computer, lowstate, lowcmd, domain_id] images: [] examples: [] open_questions: - "Exact boot time from power-on to ready" - "WiFi AP SSID naming convention" - "Full remote controller button map with diagrams" - "Default Jetson Orin NX OS and pre-installed packages" --- # Getting Started Guide Practical step-by-step guide for new G1 owners. Covers power-on to first program. ## 0. What You Have When you unbox the G1 EDU, you should have: [T0] - The G1 robot - Smart battery (quick-release, 13-cell LiPo, 9000 mAh) - Battery charger (100-240V AC input, 54V/5A DC output) - Wireless remote controller - Documentation materials The robot has two onboard computers you need to understand immediately: | Computer | IP Address | Role | Access | |---|---|---|---| | Locomotion Computer | 192.168.123.161 | Real-time motor control, balance, gait at 500 Hz | **NOT accessible** — proprietary | | Development Computer | 192.168.123.164 | Your code runs here (Jetson Orin NX 16GB) | **SSH accessible** | | LiDAR | 192.168.123.20 | Livox MID360 point cloud | Ethernet driver | ## 1. Power On ### First Boot 1. Insert the smart battery into the back of the robot (quick-release connector) 2. Press the power button 3. Wait for both computers to boot (locomotion computer + Jetson Orin) 4. The robot should enter a default standing/damping state once boot is complete ### Power Off 1. Use the remote controller or SDK to command the robot to sit/lie down 2. Press and hold the power button to shut down 3. Wait for complete shutdown before removing battery ### Charging - Plug the charger into the battery (can charge while installed or removed) - Charger output: 54V / 5A - Full charge takes approximately 2 hours - Store batteries at ~50% charge if not using for extended periods [T3 — Standard LiPo practice] ## 2. Connect to the Robot The G1 network is on the **192.168.123.0/24** subnet with **no DHCP server**. You must configure your machine's IP manually. [T0] ### Option A: WiFi Connection 1. Look for the G1's WiFi network on your development machine (WiFi 6 / 802.11ax) 2. Connect to it 3. Manually set your machine's IP to `192.168.123.X` where X is NOT 161, 164, or 20 - Example: `192.168.123.100` - Subnet mask: `255.255.255.0` 4. Test: `ping 192.168.123.164` ### Option B: Ethernet Connection (Recommended for Development) 1. Connect an Ethernet cable between your machine and the robot 2. Configure your machine's IP manually (same rules as WiFi) 3. Lower latency than WiFi — preferred for real-time control 4. Test: `ping 192.168.123.164` ### SSH Into the Jetson ```bash ssh unitree@192.168.123.164 # Password: 123 ``` [T1 — Weston Robot development guide] This is the development computer (Jetson Orin NX). Your code runs here for production, though you can also develop on an external machine connected to the same network. ### Internet Access on the Jetson The robot's network is isolated by default. To get internet on the Jetson (for installing packages): - **USB WiFi adapter:** Plug into the Jetson's USB port, connect to your WiFi - **Ethernet routing:** Connect through a router configured for the 192.168.123.0/24 subnet [T1 — Weston Robot guide] ## 3. The Wireless Remote Controller The included wireless remote controller is your primary interface for basic operation and your safety lifeline. ### Critical Controls | Function | How | Notes | |---|---|---| | **E-Stop** | Dedicated emergency stop button | ALWAYS know where this is. Memorize it before powering on. | | Stand up | High-level command via remote | Robot rises from sitting/lying | | Sit down | High-level command via remote | Safe resting position | | Walk | Joystick control | Left stick: forward/backward + turn. Right stick: lateral | | **Debug Mode** | **L2 + R2** (while suspended in damping state) | Disables stock locomotion controller for full low-level control | [T1 — Weston Robot guide for debug mode; T2 — Community for walk controls] ### Debug Mode (IMPORTANT) Pressing **L2 + R2** while the robot is suspended (on a stand/harness) and in damping state activates debug mode. This **disables Unitree's locomotion controller** and gives you full low-level joint control via `rt/lowcmd`. **WARNING:** In debug mode, the robot has NO balance. It will fall if not supported. Only use this when the robot is on a stand or safety harness. [T1] ## 4. Install the SDK ### CycloneDDS 0.10.2 (CRITICAL — Must Be Exact Version) This is the #1 gotcha. Using any other version causes **silent communication failures** — you'll get no data and no error messages. [T1] The Jetson comes with CycloneDDS pre-installed. If you're setting up an external dev machine: ```bash # Clone the exact version git clone -b 0.10.2 https://github.com/eclipse-cyclonedds/cyclonedds.git cd cyclonedds mkdir build && cd build cmake .. -DCMAKE_INSTALL_PREFIX=/usr/local make -j$(nproc) sudo make install # Set environment variable (add to ~/.bashrc) export CYCLONEDDS_HOME='/usr/local' ``` On the Jetson itself, the environment variable should be: ```bash export CYCLONEDDS_HOME='/home/unitree/cyclonedds/install' ``` [T1 — Robonomics experience report confirmed this path] ### Python SDK (Recommended for Getting Started) ```bash # On the Jetson or your dev machine git clone https://github.com/unitreerobotics/unitree_sdk2_python.git cd unitree_sdk2_python pip3 install -e . ``` If install fails, it's usually because CycloneDDS isn't properly set up. Verify `CYCLONEDDS_HOME` is set and the library was built from source. [T1] ### C++ SDK (For Production / Real-Time) ```bash # Dependencies sudo apt install cmake libyaml-cpp-dev libeigen3-dev libboost-all-dev libspdlog-dev libfmt-dev # Build git clone https://github.com/unitreerobotics/unitree_sdk2.git cd unitree_sdk2 mkdir build && cd build cmake .. && make sudo make install ``` ## 5. Your First Program: Read Robot State Before sending any commands, just **read** the robot's state. This verifies your SDK installation, network connection, and DDS communication. ### Python — Read Joint States ```python """ First program: read and print G1 joint states. Run on the Jetson or any machine on the 192.168.123.0/24 network. """ import time from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize from unitree_sdk2py.idl.unitree_hg.msg.dds_ import LowState_ def lowstate_callback(msg: LowState_): # Print first 6 motor positions (left leg) print("Left leg joints:", [f"{msg.motor_state[i].q:.3f}" for i in range(6)]) # Print IMU orientation print("IMU quaternion:", msg.imu_state.quaternion) print("---") def main(): # Initialize DDS channel # For real robot: use your network interface name (e.g., "enp2s0", "eth0") # For simulation: use domain ID (e.g., "lo" for localhost) ChannelFactoryInitialize(0, "enp2s0") # <-- CHANGE THIS to your interface # Subscribe to low-level state sub = ChannelSubscriber("rt/lowstate", LowState_) sub.Init(lowstate_callback, 10) print("Listening for robot state... (Ctrl+C to stop)") while True: time.sleep(1) if __name__ == "__main__": main() ``` ### Finding Your Network Interface Name ```bash # On your machine, find which interface is on the 192.168.123.x subnet ip addr show | grep 192.168.123 # Look for the interface name (e.g., enp2s0, eth0, wlan0) ``` ### What You Should See - Joint positions in radians (29 motors for 29-DOF variant) - IMU quaternion (orientation) - Data updating at 500 Hz ### What If You See Nothing? | Symptom | Likely Cause | Fix | |---|---|---| | No data at all | CycloneDDS version wrong | Rebuild exactly v0.10.2 | | No data at all | Wrong network interface | Check `ip addr`, use correct name | | No data at all | Robot not booted | Wait longer, verify with ping | | Import error | SDK not installed | Re-run `pip3 install -e .` | | Permission error | DDS multicast issue | Try running with `sudo` or check firewall | ## 6. Walk It Around (Remote Controller) Before writing any motion code, use the wireless remote to get familiar with the robot's capabilities: 1. Power on, wait for boot 2. Use remote to command stand-up 3. Use joysticks to walk forward, backward, turn, strafe 4. Practice stopping smoothly 5. **Test the e-stop** — press it deliberately so you know what happens and how to recover 6. Push the robot gently while standing — observe how the stock controller responds 7. Command sit-down when done This builds essential intuition. You'll need to know what "normal" looks and sounds like before deploying custom code. ## 7. Set Up Simulation Run the same programs in simulation before touching the real robot. [T0] ### MuJoCo Simulator (unitree_mujoco) ```bash # Install MuJoCo Python pip3 install mujoco # Clone simulator git clone https://github.com/unitreerobotics/unitree_mujoco.git cd unitree_mujoco # Python simulation cd simulate_python pip3 install pygame # For joystick support (optional) python3 unitree_mujoco.py ``` ### Key Point: Same API, Different Network Config The simulator uses the **same DDS topics** (`rt/lowstate`, `rt/lowcmd`) as the real robot. Your code doesn't change — only the network configuration: | Environment | ChannelFactoryInitialize | |---|---| | Real robot | `ChannelFactoryInitialize(0, "enp2s0")` | | Simulation | `ChannelFactoryInitialize(1, "lo")` (domain ID 1, localhost) | This means you can develop and test in sim, then deploy to real by changing one line. [T0] ## 8. Your First Command: Move a Joint (IN SIMULATION FIRST) **NEVER run untested motion code on the real robot.** Always validate in simulation first. ### Important: Ankle Joint Example (Safe Starting Point) The `g1_ankle_swing_example` from Weston Robot demonstrates low-level control on the ankle joints, which doesn't conflict with the standard locomotion controller. This is a safe first command because ankle motion during standing doesn't destabilize the robot. [T1 — Weston Robot guide] ### General Pattern for Sending Commands ```python """ Simplified pattern — validate in simulation first! """ from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize from unitree_sdk2py.idl.unitree_hg.msg.dds_ import LowCmd_ import time # Initialize for SIMULATION (domain ID 1, localhost) ChannelFactoryInitialize(1, "lo") pub = ChannelPublisher("rt/lowcmd", LowCmd_) pub.Init() cmd = LowCmd_() # Set a single joint target (e.g., left ankle pitch) # JOINT INDEX MATTERS — check joint-configuration.md for the mapping cmd.motor_cmd[JOINT_INDEX].mode = 1 # Enable cmd.motor_cmd[JOINT_INDEX].q = 0.1 # Target position (radians) cmd.motor_cmd[JOINT_INDEX].dq = 0.0 # Target velocity cmd.motor_cmd[JOINT_INDEX].tau = 0.0 # Feed-forward torque cmd.motor_cmd[JOINT_INDEX].kp = 50.0 # Position gain cmd.motor_cmd[JOINT_INDEX].kd = 5.0 # Velocity gain # Publish at 500 Hz while True: pub.Write(cmd) time.sleep(0.002) # 2ms = 500 Hz ``` **WARNING:** Incorrect joint indices or gains can cause violent motion. Start with very low gains (kp=10, kd=1) and increase gradually. See [[joint-configuration]] for joint indices. [T2] ## 9. Progression Path After completing steps 1-8, here's the recommended order for building toward mocap + balance: ``` Level 1: Basics (you are here) ├── Read robot state ✓ ├── Walk with remote ✓ ├── Run simulation ✓ └── Send first joint command (in sim) Level 2: SDK Fluency ├── High-level sport mode API (walk/stand/sit via code) ├── Read all sensor data (IMU, joints, camera) ├── Record and replay joint trajectories (in sim) └── Understand joint indices and limits Level 3: Simulation Development ├── Set up unitree_rl_gym (Isaac Gym training) ├── Train a basic locomotion policy ├── Validate in MuJoCo (Sim2Sim) └── Apply external forces in sim (push testing) Level 4: Toward Your Goals ├── Train push-robust locomotion policy (perturbation curriculum) ├── Set up GR00T-WBC ├── Motion retargeting (AMASS dataset → G1) └── Combined: mocap + balance See: [[push-recovery-balance]] §8, [[whole-body-control]], [[motion-retargeting]] ``` ## 10. Common Mistakes (From Community Experience) | Mistake | Consequence | Prevention | |---|---|---| | Wrong CycloneDDS version | Silent failure — no data, no errors | Always use exactly 0.10.2 | | Testing motion code on real robot first | Falls, hardware damage | Always simulate first | | Not knowing the e-stop | Can't stop runaway behavior | Test e-stop before doing anything else | | Wrong network interface name | SDK can't find robot | Use `ip addr` to find correct interface | | Sending commands without reading state first | Blind control | Always subscribe to `rt/lowstate` first | | Forgetting `CYCLONEDDS_HOME` env var | SDK build/import failures | Add to `~/.bashrc` permanently | | Using WiFi for real-time control | Variable latency, instability | Use Ethernet or develop on Jetson | | High PD gains on first test | Violent jerky motion | Start with very low gains, increase gradually | | Not charging battery before testing | Robot dies mid-test | Check battery > 30% before every session | ## Key Relationships - Leads to: [[deployment-operations]] (full operational procedures) - Requires: [[sdk-programming]] (SDK installation and API details) - Uses: [[networking-comms]] (network setup, IP addresses) - Guided by: [[safety-limits]] (what not to do) - Practice in: [[simulation]] (always sim before real) - Joint reference: [[joint-configuration]] (joint indices, limits) - Goal: [[whole-body-control]] → [[motion-retargeting]] → [[push-recovery-balance]]