forked from real-stanford/diffusion_policy
-
Notifications
You must be signed in to change notification settings - Fork 2
/
crossway_diffusion_unet_hybrid_image_policy.py
393 lines (347 loc) · 14.8 KB
/
crossway_diffusion_unet_hybrid_image_policy.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
from typing import Dict
import math
import torch
import torch.nn as nn
import torch.nn.functional as F
from einops import rearrange, reduce
from diffusers.schedulers.scheduling_ddpm import DDPMScheduler
from diffusion_policy.model.common.normalizer import LinearNormalizer
from diffusion_policy.policy.base_image_policy import BaseImagePolicy
from diffusion_policy.model.diffusion.conditional_unet1d import ConditionalUnet1DwDecTypeA, ConditionalUnet1DwDecTypeB, ConditionalUnet1DwDecTypeC, ConditionalUnet1DwDecTypeD
from diffusion_policy.model.diffusion.mask_generator import LowdimMaskGenerator
from diffusion_policy.common.robomimic_config_util import get_robomimic_config
from robomimic.algo import algo_factory
from robomimic.algo.algo import PolicyAlgo
import robomimic.utils.obs_utils as ObsUtils
import robomimic.models.base_nets as rmbn
import diffusion_policy.model.vision.crop_randomizer as dmvc
from diffusion_policy.common.pytorch_util import dict_apply, replace_submodules
import torchvision.transforms as T
class AEDiffusionUnetHybridImagePolicy(BaseImagePolicy):
def __init__(self,
shape_meta: dict,
noise_scheduler: DDPMScheduler,
horizon,
n_action_steps,
n_obs_steps,
num_inference_steps=None,
obs_as_global_cond=True,
crop_shape=(76, 76),
diffusion_step_embed_dim=256,
down_dims=(256,512,1024),
kernel_size=5,
n_groups=8,
cond_predict_scale=True,
obs_encoder_group_norm=False,
eval_fixed_crop=False,
decode_unet_feat=True,
decode_pe_dim=64,
decode_resolution=2,
decode_dims=(64, 128),
decode_low_dim_dims=(2, 4),
decode_ver='a',
# parameters passed to step
**kwargs):
super().__init__()
# parse shape_meta
action_shape = shape_meta['action']['shape']
assert len(action_shape) == 1
action_dim = action_shape[0]
obs_shape_meta = shape_meta['obs']
obs_config = {
'low_dim': [],
'rgb': [],
'depth': [],
'scan': []
}
obs_key_shapes = dict()
for key, attr in obs_shape_meta.items():
shape = attr['shape']
obs_key_shapes[key] = list(shape)
type = attr.get('type', 'low_dim')
if type == 'rgb':
obs_config['rgb'].append(key)
elif type == 'low_dim':
obs_config['low_dim'].append(key)
else:
raise RuntimeError(f"Unsupported obs type: {type}")
# get raw robomimic config
config = get_robomimic_config(
algo_name='bc_rnn',
hdf5_type='image',
task_name='square',
dataset_type='ph')
with config.unlocked():
# set config with shape_meta
config.observation.modalities.obs = obs_config
if crop_shape is None:
for key, modality in config.observation.encoder.items():
if modality.obs_randomizer_class == 'CropRandomizer':
modality['obs_randomizer_class'] = None
else:
# set random crop parameter
ch, cw = crop_shape
for key, modality in config.observation.encoder.items():
if modality.obs_randomizer_class == 'CropRandomizer':
modality.obs_randomizer_kwargs.crop_height = ch
modality.obs_randomizer_kwargs.crop_width = cw
# init global state
ObsUtils.initialize_obs_utils_with_config(config)
# load model
policy: PolicyAlgo = algo_factory(
algo_name=config.algo_name,
config=config,
obs_key_shapes=obs_key_shapes,
ac_dim=action_dim,
device='cpu',
)
obs_encoder = policy.nets['policy'].nets['encoder'].nets['obs']
if obs_encoder_group_norm:
# replace batch norm with group norm
replace_submodules(
root_module=obs_encoder,
predicate=lambda x: isinstance(x, nn.BatchNorm2d),
func=lambda x: nn.GroupNorm(
num_groups=x.num_features//16,
num_channels=x.num_features)
)
# obs_encoder.obs_nets['agentview_image'].nets[0].nets
# obs_encoder.obs_randomizers['agentview_image']
if eval_fixed_crop:
replace_submodules(
root_module=obs_encoder,
predicate=lambda x: isinstance(x, rmbn.CropRandomizer),
func=lambda x: dmvc.CropRandomizer(
input_shape=x.input_shape,
crop_height=x.crop_height,
crop_width=x.crop_width,
num_crops=x.num_crops,
pos_enc=x.pos_enc
)
)
# create diffusion model
obs_feature_dim = obs_encoder.output_shape()[0]
input_dim = action_dim + obs_feature_dim
global_cond_dim = None
if obs_as_global_cond:
input_dim = action_dim
global_cond_dim = obs_feature_dim * n_obs_steps
if decode_ver == 'a' or decode_ver == 'v1':
mymodel = ConditionalUnet1DwDecTypeA
elif decode_ver == 'b' or decode_ver == 'v3':
mymodel = ConditionalUnet1DwDecTypeB
elif decode_ver == 'c' or decode_ver == 'v2':
mymodel = ConditionalUnet1DwDecTypeC
elif decode_ver == 'd':
mymodel = ConditionalUnet1DwDecTypeD
else:
raise NotImplementedError(f'Unknown decoder type: {decode_ver}')
model = mymodel(
input_dim=input_dim,
n_obs_steps=n_obs_steps,
obs_shape_meta=obs_shape_meta,
decode_unet_feat=decode_unet_feat,
decode_pe_dim=decode_pe_dim,
decode_resolution=decode_resolution,
decode_dims=decode_dims,
decode_low_dim_dims=decode_low_dim_dims,
local_cond_dim=None,
global_cond_dim=global_cond_dim,
diffusion_step_embed_dim=diffusion_step_embed_dim,
down_dims=down_dims,
kernel_size=kernel_size,
n_groups=n_groups,
cond_predict_scale=cond_predict_scale,
)
self.obs_encoder = obs_encoder
self.model = model
self.noise_scheduler = noise_scheduler
self.mask_generator = LowdimMaskGenerator(
action_dim=action_dim,
obs_dim=0 if obs_as_global_cond else obs_feature_dim,
max_n_obs_steps=n_obs_steps,
fix_obs_steps=True,
action_visible=False
)
self.normalizer = LinearNormalizer()
self.horizon = horizon
self.obs_feature_dim = obs_feature_dim
self.obs_shape_meta = obs_shape_meta
self.action_dim = action_dim
self.n_action_steps = n_action_steps
self.n_obs_steps = n_obs_steps
self.obs_as_global_cond = obs_as_global_cond
self.kwargs = kwargs
if num_inference_steps is None:
num_inference_steps = noise_scheduler.config.num_train_timesteps
self.num_inference_steps = num_inference_steps
print("Diffusion params: %e" % sum(p.numel() for p in self.model.parameters()))
print("Vision params: %e" % sum(p.numel() for p in self.obs_encoder.parameters()))
# ========= inference ============
def conditional_sample(self,
condition_data, condition_mask,
local_cond=None, global_cond=None,
generator=None,
# keyword arguments to scheduler.step
**kwargs
):
model = self.model
scheduler = self.noise_scheduler
trajectory = torch.randn(
size=condition_data.shape,
dtype=condition_data.dtype,
device=condition_data.device,
generator=generator)
# set step values
scheduler.set_timesteps(self.num_inference_steps)
for t in scheduler.timesteps:
# 1. apply conditioning
trajectory[condition_mask] = condition_data[condition_mask]
# 2. predict model output
model_output = model(trajectory, t,
local_cond=local_cond, global_cond=global_cond)
# 3. compute previous image: x_t -> x_t-1
trajectory = scheduler.step(
model_output, t, trajectory,
generator=generator,
**kwargs
).prev_sample
# finally make sure conditioning is enforced
trajectory[condition_mask] = condition_data[condition_mask]
return trajectory
def predict_action(self, obs_dict: Dict[str, torch.Tensor]) -> Dict[str, torch.Tensor]:
"""
obs_dict: must include "obs" key
result: must include "action" key
"""
assert 'past_action' not in obs_dict # not implemented yet
# normalize input
nobs = self.normalizer.normalize(obs_dict)
value = next(iter(nobs.values()))
B, To = value.shape[:2]
T = self.horizon
Da = self.action_dim
Do = self.obs_feature_dim
To = self.n_obs_steps
# build input
device = self.device
dtype = self.dtype
# handle different ways of passing observation
local_cond = None
global_cond = None
if self.obs_as_global_cond:
# condition through global feature
this_nobs = dict_apply(nobs, lambda x: x[:,:To,...].reshape(-1,*x.shape[2:]))
nobs_features = self.obs_encoder(this_nobs)
# reshape back to B, Do
global_cond = nobs_features.reshape(B, -1)
# empty data for action
cond_data = torch.zeros(size=(B, T, Da), device=device, dtype=dtype)
cond_mask = torch.zeros_like(cond_data, dtype=torch.bool)
else:
# condition through impainting
this_nobs = dict_apply(nobs, lambda x: x[:,:To,...].reshape(-1,*x.shape[2:]))
nobs_features = self.obs_encoder(this_nobs)
# reshape back to B, T, Do
nobs_features = nobs_features.reshape(B, To, -1)
cond_data = torch.zeros(size=(B, T, Da+Do), device=device, dtype=dtype)
cond_mask = torch.zeros_like(cond_data, dtype=torch.bool)
cond_data[:,:To,Da:] = nobs_features
cond_mask[:,:To,Da:] = True
# run sampling
nsample = self.conditional_sample(
cond_data,
cond_mask,
local_cond=local_cond,
global_cond=global_cond,
**self.kwargs)
# unnormalize prediction
naction_pred = nsample[...,:Da]
action_pred = self.normalizer['action'].unnormalize(naction_pred)
# get action
start = To - 1
end = start + self.n_action_steps
action = action_pred[:,start:end]
result = {
'action': action,
'action_pred': action_pred
}
return result
# ========= training ============
def set_normalizer(self, normalizer: LinearNormalizer):
self.normalizer.load_state_dict(normalizer.state_dict())
def compute_loss(self, batch):
# normalize input
assert 'valid_mask' not in batch
nobs = self.normalizer.normalize(batch['obs'])
# nobs['image'] 64 x 16 x 3 x 96 x 96
# nobs['agent_pos'] 64 x 16 x 2
nactions = self.normalizer['action'].normalize(batch['action'])
# nactions 64 x 16 x 2
batch_size = nactions.shape[0]
horizon = nactions.shape[1]
# handle different ways of passing observation
local_cond = None
global_cond = None
trajectory = nactions
cond_data = trajectory
if self.obs_as_global_cond: # true by default
# reshape B, T, ... to B*T
this_nobs = dict_apply(nobs,
lambda x: x[:,:self.n_obs_steps,...].reshape(-1,*x.shape[2:])) # image: 128, 3, 96, 96
nobs_features = self.obs_encoder(this_nobs) # shape: 128, 66
# reshape back to B, Do
global_cond = nobs_features.reshape(batch_size, -1) # shape: 64, 132
else:
# reshape B, T, ... to B*T
this_nobs = dict_apply(nobs, lambda x: x.reshape(-1, *x.shape[2:]))
nobs_features = self.obs_encoder(this_nobs)
# reshape back to B, T, Do
nobs_features = nobs_features.reshape(batch_size, horizon, -1)
cond_data = torch.cat([nactions, nobs_features], dim=-1)
trajectory = cond_data.detach()
# generate impainting mask
condition_mask = self.mask_generator(trajectory.shape)
# Sample noise that we'll add to the images
noise = torch.randn(trajectory.shape, device=trajectory.device)
bsz = trajectory.shape[0]
# Sample a random timestep for each image
timesteps = torch.randint(
0, self.noise_scheduler.config.num_train_timesteps,
(bsz,), device=trajectory.device
).long()
# Add noise to the clean images according to the noise magnitude at each timestep
# (this is the forward diffusion process)
noisy_trajectory = self.noise_scheduler.add_noise(
trajectory, noise, timesteps)
# compute loss mask
loss_mask = ~condition_mask
# apply conditioning
noisy_trajectory[condition_mask] = cond_data[condition_mask]
# Predict the noise residual
pred, recons = self.model.forward_and_recon(noisy_trajectory, timesteps,
local_cond=local_cond, global_cond=global_cond)
# local_cond is None, global_cond shape = 64, 132 (66 for each image)
pred_type = self.noise_scheduler.config.prediction_type
if pred_type == 'epsilon':
target = noise
elif pred_type == 'sample':
target = trajectory
else:
raise ValueError(f"Unsupported prediction type {pred_type}")
loss = F.mse_loss(pred, target, reduction='none')
loss = loss * loss_mask.type(loss.dtype)
loss = reduce(loss, 'b ... -> b (...)', 'mean')
loss = loss.mean()
losses = {'diffusion': loss}
total_loss = loss
for key, rec in recons.items():
if rec.shape != this_nobs[key].shape:
rec_target = T.Resize(rec.shape[-2:])(this_nobs[key])
else:
rec_target = this_nobs[key]
aux_loss = F.mse_loss(rec, rec_target) * self.obs_shape_meta[key]['dec_loss_weight']
total_loss += aux_loss
losses[key] = aux_loss.item()
unnorm_recons = self.normalizer.unnormalize(recons)
return total_loss, losses, unnorm_recons