gpue commited on
Commit
45293be
·
1 Parent(s): b04cadc

Add Docker support with Dockerfile, docker-compose.yml, and .dockerignore

Browse files

- Introduced Dockerfile for building the application with necessary system dependencies for MuJoCo and OpenCV.
- Added docker-compose.yml to define the service configuration for the Nova Sim application.
- Created .dockerignore to exclude unnecessary files from the Docker build context.
- Updated SpotEnv and TrotGaitController comments for clarity on standing pose definitions.

.dockerignore ADDED
@@ -0,0 +1,60 @@
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
+ # Python
2
+ __pycache__/
3
+ *.py[cod]
4
+ *$py.class
5
+ *.so
6
+ .Python
7
+ build/
8
+ develop-eggs/
9
+ dist/
10
+ downloads/
11
+ eggs/
12
+ .eggs/
13
+ lib/
14
+ lib64/
15
+ parts/
16
+ sdist/
17
+ var/
18
+ wheels/
19
+ *.egg-info/
20
+ .installed.cfg
21
+ *.egg
22
+
23
+ # Virtual environments
24
+ venv/
25
+ ENV/
26
+ env/
27
+ .venv/
28
+
29
+ # IDEs
30
+ .idea/
31
+ .vscode/
32
+ *.swp
33
+ *.swo
34
+ *~
35
+
36
+ # OS
37
+ .DS_Store
38
+ Thumbs.db
39
+
40
+ # Claude
41
+ .claude/
42
+
43
+ # Git
44
+ .git/
45
+ .gitignore
46
+
47
+ # Docker
48
+ Dockerfile
49
+ .dockerignore
50
+ docker-compose.yml
51
+
52
+ # Jupyter
53
+ .ipynb_checkpoints/
54
+
55
+ # MuJoCo compiled
56
+ *.mjb
57
+
58
+ # Test files
59
+ tests/
60
+ *.test.py
Dockerfile ADDED
@@ -0,0 +1,54 @@
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
+ FROM python:3.11-slim-bookworm
2
+
3
+ # Install system dependencies for MuJoCo and OpenCV
4
+ RUN apt-get update && apt-get install -y \
5
+ libgl1 \
6
+ libglx0 \
7
+ libglib2.0-0 \
8
+ libsm6 \
9
+ libxext6 \
10
+ libxrender1 \
11
+ libgomp1 \
12
+ libglfw3 \
13
+ libglew2.2 \
14
+ libosmesa6 \
15
+ libegl1 \
16
+ git \
17
+ && rm -rf /var/lib/apt/lists/*
18
+
19
+ # Set working directory
20
+ WORKDIR /app
21
+
22
+ # Copy requirements first for better caching
23
+ COPY requirements.txt .
24
+
25
+ # Install Python dependencies
26
+ RUN pip install --no-cache-dir -r requirements.txt
27
+
28
+ # Clone MuJoCo Menagerie for Spot model
29
+ RUN git clone --depth 1 https://github.com/google-deepmind/mujoco_menagerie.git /mujoco_menagerie
30
+
31
+ # Clone unitree_rl_gym for G1 RL policy
32
+ RUN git clone --depth 1 https://github.com/unitreerobotics/unitree_rl_gym.git /unitree_rl_gym
33
+
34
+ # Copy application code
35
+ COPY . .
36
+
37
+ # Update paths in the code to use container paths
38
+ # G1 RL policy path
39
+ RUN sed -i 's|robotsim_parent_dir = os.path.dirname(nova_sim_dir)|robotsim_parent_dir = "/"|g' \
40
+ /app/robots/g1/controllers/rl_policy.py
41
+
42
+ # Spot model path
43
+ RUN sed -i 's|robotsim_parent_dir = os.path.dirname(nova_sim_dir)|robotsim_parent_dir = "/"|g' \
44
+ /app/robots/spot/spot_env.py
45
+
46
+ # Environment variables for headless rendering
47
+ ENV MUJOCO_GL=osmesa
48
+ ENV PYOPENGL_PLATFORM=osmesa
49
+
50
+ # Expose port
51
+ EXPOSE 3004
52
+
53
+ # Run the server
54
+ CMD ["python", "mujoco_server.py"]
docker-compose.yml ADDED
@@ -0,0 +1,11 @@
 
 
 
 
 
 
 
 
 
 
 
 
1
+ version: '3.8'
2
+
3
+ services:
4
+ nova-sim:
5
+ build: .
6
+ ports:
7
+ - "3004:3004"
8
+ environment:
9
+ - MUJOCO_GL=osmesa
10
+ - PYOPENGL_PLATFORM=osmesa
11
+ restart: unless-stopped
robots/spot/controllers/trot_gait.py CHANGED
@@ -20,7 +20,7 @@ class TrotGaitController(BaseController):
20
  Uses simple sinusoidal trajectories for leg motion.
21
  """
22
 
23
- # Standing pose
24
  STANDING_POSE = np.array([
25
  0.0, 1.04, -1.8, # FL: hx, hy, kn
26
  0.0, 1.04, -1.8, # FR
@@ -28,29 +28,20 @@ class TrotGaitController(BaseController):
28
  0.0, 1.04, -1.8, # HR
29
  ], dtype=np.float32)
30
 
31
- # Joint indices
32
- FL_HX, FL_HY, FL_KN = 0, 1, 2
33
- FR_HX, FR_HY, FR_KN = 3, 4, 5
34
- HL_HX, HL_HY, HL_KN = 6, 7, 8
35
- HR_HX, HR_HY, HR_KN = 9, 10, 11
36
-
37
  def __init__(self, num_joints: int = 12):
38
  super().__init__(num_joints)
39
 
40
  # Velocity command [vx, vy, vyaw]
41
  self.cmd = np.array([0.0, 0.0, 0.0], dtype=np.float32)
42
 
43
- # Gait parameters
44
- self.gait_freq = 2.0 # Hz - steps per second
45
- self.step_height = 0.08 # meters - how high to lift feet
46
- self.stride_length = 0.15 # meters - forward stride
47
 
48
  # Phase offset for trot (diagonal pairs in sync)
49
  # FL and HR at phase 0, FR and HL at phase 0.5
50
- self.phase_offsets = np.array([0.0, 0.0, 0.5, 0.5]) # FL, FR, HL, HR
51
-
52
- # Smooth startup
53
- self.ramp_time = 1.0
54
 
55
  def set_command(self, vx: float = 0.0, vy: float = 0.0, vyaw: float = 0.0):
56
  """Set velocity command for the robot."""
@@ -62,118 +53,80 @@ class TrotGaitController(BaseController):
62
  """Get current velocity command."""
63
  return self.cmd.copy()
64
 
65
- def _leg_trajectory(self, phase: float, vx: float, vy: float, vyaw: float, leg_idx: int):
66
- """
67
- Compute leg joint angles for a given gait phase.
68
-
69
- Args:
70
- phase: Gait phase [0, 1)
71
- vx: Forward velocity command
72
- vy: Lateral velocity command
73
- vyaw: Yaw rate command
74
- leg_idx: Leg index (0=FL, 1=FR, 2=HL, 3=HR)
75
-
76
- Returns:
77
- (hx, hy, kn) joint angles
78
- """
79
- # Base standing angles
80
- hx_base, hy_base, kn_base = 0.0, 1.04, -1.8
81
-
82
- # Speed factor (0-1) based on command magnitude
83
- speed = np.sqrt(vx**2 + vy**2 + vyaw**2)
84
- speed_factor = min(1.0, speed / 1.0)
85
-
86
- if speed_factor < 0.05:
87
- # Standing - no motion
88
- return hx_base, hy_base, kn_base
89
-
90
- # Leg position relative to body center
91
- # FL: (+x, +y), FR: (+x, -y), HL: (-x, +y), HR: (-x, -y)
92
- leg_signs = [
93
- (1, 1), # FL
94
- (1, -1), # FR
95
- (-1, 1), # HL
96
- (-1, -1), # HR
97
- ]
98
- sign_x, sign_y = leg_signs[leg_idx]
99
-
100
- # Swing/stance phase
101
- # phase < 0.5: swing (foot in air)
102
- # phase >= 0.5: stance (foot on ground)
103
- is_swing = phase < 0.5
104
- swing_phase = phase / 0.5 if is_swing else 0.0
105
- stance_phase = (phase - 0.5) / 0.5 if not is_swing else 0.0
106
-
107
- # Hip pitch (hy) - controls forward/backward leg motion
108
- stride = self.stride_length * speed_factor * vx
109
- if is_swing:
110
- # Swing forward
111
- hy_offset = stride * (swing_phase - 0.5)
112
- else:
113
- # Push backward
114
- hy_offset = stride * (0.5 - stance_phase)
115
-
116
- # Knee (kn) - lift foot during swing
117
- if is_swing:
118
- # Lift foot using sinusoidal trajectory
119
- lift = self.step_height * np.sin(np.pi * swing_phase)
120
- kn_offset = lift * 2.0 # Convert to knee angle change
121
- else:
122
- kn_offset = 0.0
123
-
124
- # Hip roll (hx) - lateral motion and turning
125
- hx_offset = 0.0
126
-
127
- # Lateral motion
128
- if abs(vy) > 0.01:
129
- lateral_stride = 0.1 * speed_factor * vy * sign_y
130
- if is_swing:
131
- hx_offset += lateral_stride * (swing_phase - 0.5)
132
- else:
133
- hx_offset += lateral_stride * (0.5 - stance_phase)
134
-
135
- # Turning - differential stride
136
- if abs(vyaw) > 0.01:
137
- turn_factor = 0.1 * vyaw * sign_y
138
- if is_swing:
139
- hy_offset += turn_factor * (swing_phase - 0.5)
140
- else:
141
- hy_offset += turn_factor * (0.5 - stance_phase)
142
-
143
- return hx_base + hx_offset, hy_base + hy_offset, kn_base + kn_offset
144
-
145
  def compute_action(self, obs: np.ndarray, data) -> np.ndarray:
146
  """Compute target joint positions for trot gait."""
147
- # Smooth startup ramp
148
- gain = min(1.0, self.time / self.ramp_time) if self.ramp_time > 0 else 1.0
149
 
150
- # Compute gait phase
151
- gait_phase = (self.time * self.gait_freq) % 1.0
 
 
 
152
 
153
- # Get command
154
- vx, vy, vyaw = self.cmd
 
 
 
 
155
 
156
- # Compute joint targets for each leg
157
  target = np.zeros(12, dtype=np.float32)
158
 
159
  for leg_idx in range(4):
160
- # Apply phase offset for this leg
161
- leg_phase = (gait_phase + self.phase_offsets[leg_idx]) % 1.0
162
 
163
- # Get joint angles
164
- hx, hy, kn = self._leg_trajectory(leg_phase, vx, vy, vyaw, leg_idx)
165
 
166
- # Store in target array
167
- base_idx = leg_idx * 3
168
- target[base_idx] = hx
169
- target[base_idx + 1] = hy
170
- target[base_idx + 2] = kn
 
 
 
 
 
 
 
 
 
 
171
 
172
- # Blend with standing pose during startup
173
- standing = self.STANDING_POSE.copy()
174
- result = standing + gain * (target - standing)
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
175
 
176
- return result
177
 
178
  def reset(self):
179
  super().reset()
 
20
  Uses simple sinusoidal trajectories for leg motion.
21
  """
22
 
23
+ # Standing pose - from model's "home" keyframe
24
  STANDING_POSE = np.array([
25
  0.0, 1.04, -1.8, # FL: hx, hy, kn
26
  0.0, 1.04, -1.8, # FR
 
28
  0.0, 1.04, -1.8, # HR
29
  ], dtype=np.float32)
30
 
 
 
 
 
 
 
31
  def __init__(self, num_joints: int = 12):
32
  super().__init__(num_joints)
33
 
34
  # Velocity command [vx, vy, vyaw]
35
  self.cmd = np.array([0.0, 0.0, 0.0], dtype=np.float32)
36
 
37
+ # Gait parameters - tuned for visible motion
38
+ self.gait_freq = 2.0 # Hz - gait cycles per second
39
+ self.swing_height = 0.3 # How much to bend knee during swing (radians)
40
+ self.stride_length = 0.25 # Hip pitch amplitude (radians)
41
 
42
  # Phase offset for trot (diagonal pairs in sync)
43
  # FL and HR at phase 0, FR and HL at phase 0.5
44
+ self.phase_offsets = np.array([0.0, 0.5, 0.5, 0.0]) # FL, FR, HL, HR
 
 
 
45
 
46
  def set_command(self, vx: float = 0.0, vy: float = 0.0, vyaw: float = 0.0):
47
  """Set velocity command for the robot."""
 
53
  """Get current velocity command."""
54
  return self.cmd.copy()
55
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
56
  def compute_action(self, obs: np.ndarray, data) -> np.ndarray:
57
  """Compute target joint positions for trot gait."""
58
+ vx, vy, vyaw = self.cmd
 
59
 
60
+ # Check if we should be walking
61
+ speed = np.sqrt(vx**2 + vy**2 + vyaw**2)
62
+ if speed < 0.05:
63
+ # Just stand
64
+ return self.STANDING_POSE.copy()
65
 
66
+ # Gait phase (0 to 1)
67
+ phase = (self.time * self.gait_freq) % 1.0
68
+
69
+ # Base standing angles (from model's home keyframe)
70
+ hy_stand = 1.04 # Hip pitch
71
+ kn_stand = -1.8 # Knee
72
 
73
+ # Output array
74
  target = np.zeros(12, dtype=np.float32)
75
 
76
  for leg_idx in range(4):
77
+ # Get leg phase with offset
78
+ leg_phase = (phase + self.phase_offsets[leg_idx]) % 1.0
79
 
80
+ # Determine if in swing (0-0.5) or stance (0.5-1.0)
81
+ in_swing = leg_phase < 0.5
82
 
83
+ # Compute phase within swing or stance (0 to 1)
84
+ if in_swing:
85
+ p = leg_phase / 0.5
86
+ else:
87
+ p = (leg_phase - 0.5) / 0.5
88
+
89
+ # Hip pitch: sinusoidal forward/back motion
90
+ # During swing: leg moves forward
91
+ # During stance: leg moves backward (pushes body forward)
92
+ if in_swing:
93
+ # Swing forward: start back, end front
94
+ hy_offset = self.stride_length * vx * (p - 0.5)
95
+ else:
96
+ # Stance backward: start front, end back
97
+ hy_offset = self.stride_length * vx * (0.5 - p)
98
 
99
+ # Knee: lift during swing phase
100
+ if in_swing:
101
+ # Sinusoidal lift
102
+ kn_offset = -self.swing_height * np.sin(np.pi * p)
103
+ else:
104
+ kn_offset = 0.0
105
+
106
+ # Hip roll for turning
107
+ is_left = leg_idx in [0, 2]
108
+ hx_offset = 0.0
109
+ if abs(vyaw) > 0.01:
110
+ # Differential motion for turning
111
+ sign = 1.0 if is_left else -1.0
112
+ if in_swing:
113
+ hx_offset = sign * 0.1 * vyaw * np.sin(np.pi * p)
114
+
115
+ # Lateral motion
116
+ if abs(vy) > 0.01:
117
+ sign = 1.0 if is_left else -1.0
118
+ if in_swing:
119
+ hx_offset += sign * 0.2 * vy * (p - 0.5)
120
+ else:
121
+ hx_offset += sign * 0.2 * vy * (0.5 - p)
122
+
123
+ # Set joint targets
124
+ base_idx = leg_idx * 3
125
+ target[base_idx + 0] = hx_offset # hx (hip roll)
126
+ target[base_idx + 1] = hy_stand + hy_offset # hy (hip pitch)
127
+ target[base_idx + 2] = kn_stand + kn_offset # kn (knee)
128
 
129
+ return target
130
 
131
  def reset(self):
132
  super().reset()
robots/spot/spot_env.py CHANGED
@@ -36,10 +36,9 @@ class SpotEnv(gym.Env):
36
  "hr_hx", "hr_hy", "hr_kn",
37
  ]
38
 
39
- # Standing pose from the model's keyframe
40
- # hx=0, hy=1.04, kn=-1.8 for all legs
41
  DEFAULT_STANDING_POSE = np.array([
42
- 0.0, 1.04, -1.8, # FL
43
  0.0, 1.04, -1.8, # FR
44
  0.0, 1.04, -1.8, # HL
45
  0.0, 1.04, -1.8, # HR
 
36
  "hr_hx", "hr_hy", "hr_kn",
37
  ]
38
 
39
+ # Standing pose - from model's "home" keyframe
 
40
  DEFAULT_STANDING_POSE = np.array([
41
+ 0.0, 1.04, -1.8, # FL: hx, hy, kn
42
  0.0, 1.04, -1.8, # FR
43
  0.0, 1.04, -1.8, # HL
44
  0.0, 1.04, -1.8, # HR