Skip to content
Merged
5 changes: 4 additions & 1 deletion dimos/robot/unitree/g1/blueprints/agentic/_agentic_skills.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,15 @@

from dimos.agents.agent import agent
from dimos.agents.skills.navigation import navigation_skill
from dimos.agents.skills.speak_skill import speak_skill
from dimos.core.blueprints import autoconnect
from dimos.robot.unitree.g1.skill_container import g1_skills
from dimos.robot.unitree.g1.system_prompt import G1_SYSTEM_PROMPT

_agentic_skills = autoconnect(
agent(),
agent(system_prompt=G1_SYSTEM_PROMPT),
navigation_skill(),
speak_skill(),
g1_skills(),
)

Expand Down
32 changes: 30 additions & 2 deletions dimos/robot/unitree/g1/connection.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
# limitations under the License.


from abc import ABC, abstractmethod
from typing import TYPE_CHECKING, Any

from reactivex.disposable import Disposable
Expand All @@ -33,7 +34,34 @@
logger = setup_logger()


class G1Connection(Module):
class G1ConnectionBase(Module, ABC):
"""Abstract base for G1 connections (real hardware and simulation).

Modules that depend on G1 connection RPC methods should reference this
base class so the blueprint wiring works regardless of which concrete
connection is deployed.
"""

@rpc
@abstractmethod
def start(self) -> None:
super().start()

@rpc
@abstractmethod
def stop(self) -> None:
super().stop()

@rpc
@abstractmethod
def move(self, twist: Twist, duration: float = 0.0) -> None: ...

@rpc
@abstractmethod
def publish_request(self, topic: str, data: dict[str, Any]) -> dict[Any, Any]: ...


class G1Connection(G1ConnectionBase):
cmd_vel: In[Twist]
ip: str | None
connection_type: str | None = None
Expand Down Expand Up @@ -105,4 +133,4 @@ def deploy(dimos: ModuleCoordinator, ip: str, local_planner: spec.LocalPlanner)
return connection


__all__ = ["G1Connection", "deploy", "g1_connection"]
__all__ = ["G1Connection", "G1ConnectionBase", "deploy", "g1_connection"]
4 changes: 2 additions & 2 deletions dimos/robot/unitree/g1/sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@

from dimos.core.core import rpc
from dimos.core.global_config import GlobalConfig, global_config
from dimos.core.module import Module
from dimos.core.stream import In, Out
from dimos.msgs.geometry_msgs import (
PoseStamped,
Expand All @@ -32,6 +31,7 @@
Vector3,
)
from dimos.msgs.sensor_msgs import CameraInfo, Image, PointCloud2
from dimos.robot.unitree.g1.connection import G1ConnectionBase
from dimos.robot.unitree.type.odometry import Odometry as SimOdometry
from dimos.utils.logging_config import setup_logger

Expand Down Expand Up @@ -60,7 +60,7 @@ def _camera_info_static() -> CameraInfo:
)


class G1SimConnection(Module):
class G1SimConnection(G1ConnectionBase):
cmd_vel: In[Twist]
lidar: Out[PointCloud2]
odom: Out[PoseStamped]
Expand Down
8 changes: 4 additions & 4 deletions dimos/robot/unitree/g1/skill_container.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,8 @@

class UnitreeG1SkillContainer(Module):
rpc_calls: list[str] = [
"G1Connection.move",
"G1Connection.publish_request",
"G1ConnectionBase.move",
"G1ConnectionBase.publish_request",
]

@rpc
Expand All @@ -90,7 +90,7 @@ def move(self, x: float, y: float = 0.0, yaw: float = 0.0, duration: float = 0.0
duration: How long to move (seconds)
"""

move_rpc = self.get_rpc_calls("G1Connection.move")
move_rpc = self.get_rpc_calls("G1ConnectionBase.move")
twist = Twist(linear=Vector3(x, y, 0), angular=Vector3(0, 0, yaw))
move_rpc(twist, duration=duration)
return f"Started moving with velocity=({x}, {y}, {yaw}) for {duration} seconds"
Expand All @@ -110,7 +110,7 @@ def _execute_g1_command(
topic: str,
command_name: str,
) -> str:
publish_request_rpc = self.get_rpc_calls("G1Connection.publish_request")
publish_request_rpc = self.get_rpc_calls("G1ConnectionBase.publish_request")

if command_name not in command_dict:
suggestions = difflib.get_close_matches(
Expand Down
58 changes: 58 additions & 0 deletions dimos/robot/unitree/g1/system_prompt.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
# Copyright 2026 Dimensional Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

G1_SYSTEM_PROMPT = """
You are Daneel, an AI agent created by Dimensional to control a Unitree G1 humanoid robot.

# CRITICAL: SAFETY
Prioritize human safety above all else. Respect personal boundaries. Never take actions that could harm humans, damage property, or damage the robot.

# IDENTITY
You are Daneel. If someone says "daniel" or similar, ignore it (speech-to-text error). When greeted, briefly introduce yourself as an AI agent operating a humanoid robot.

# COMMUNICATION
Users hear you through speakers but cannot see text. Use `speak` to communicate your actions or responses. Be concise—one or two sentences.

# AVAILABLE SKILLS

## Movement
Use `move` for direct velocity control:
- `x`: forward/backward velocity (m/s). Required.
- `y`: left/right velocity (m/s). Default 0.
- `yaw`: rotational velocity (rad/s). Default 0.
- `duration`: seconds to move. Default 0.

Examples:
- Walk forward: `move(x=0.5, duration=3.0)`
- Walk backward: `move(x=-0.3, duration=2.0)`
- Turn right 90°: `move(x=0.0, yaw=-1.57, duration=1.0)`
- Turn left 90°: `move(x=0.0, yaw=1.57, duration=1.0)`

## Arm Gestures
Use `execute_arm_command` with one of these command names:
- "Handshake", "HighFive", "Hug", "HighWave", "Clap", "FaceWave"
- "LeftKiss", "ArmHeart", "RightHeart", "HandsUp", "XRay"
- "RightHandUp", "Reject", "CancelAction"

## Movement Modes
Use `execute_mode_command` with: "WalkMode", "WalkControlWaist", or "RunMode"

## Navigation
- Use `navigate_with_text` for most navigation. It searches tagged locations first, then visible objects, then the semantic map.
- Tag important locations with `tag_location` so you can return to them later.
- During `start_exploration`, avoid calling other skills except `stop_movement`.

# BEHAVIOR
Be proactive. Infer reasonable actions from ambiguous requests. Inform the user of your assumption.
"""
Loading