转载自公众号:敢敢AUTOHUB
0. 简介
LDA-1B 要解决的不是“机器人能否模仿一个动作”,而是“机器人能否从大量质量参差、来源复杂、标注不完整的数据中持续学习世界如何变化”。过去很多机器人基础模型依赖行为克隆,也就是让模型看专家怎么做,然后学习在相似观察下输出相似动作。这条路线有效,但代价很高:需要大量高质量遥操作数据,需要严格对齐动作空间,还容易把低质量轨迹、人类视频、仿真数据排除在训练之外。LDA-1B 的核心贡献,是把这些原本难以共用的数据放进一个统一的世界-动作学习框架中,让不同质量的数据承担不同训练角色。
论文地址:https://arxiv.org/abs/2602.12215
项目主页:https://pku-epic.github.io/LDA/
开源仓库:https://github.com/jiangranlv/LDA-1B
1. 为什么行为克隆不够用
行为克隆的优点很清楚:训练目标直接,工程实现相对成熟,只要有足够专家轨迹,模型就能学到“在某个画面和指令下应该怎么动”。RT-1、Octo、OpenVLA、GR00T、π0 系列等工作都推动了这条路线的发展。问题在于,行为克隆把动作标签质量放在非常核心的位置,低质量数据会直接污染策略学习。例如一个人抓杯子时失败了,传统策略模型可能会把失败动作也当成可模仿对象;但从动力学角度看,杯子被碰倒后的运动过程仍然是真实物理反馈,不能简单视为无用数据。
论文对这个问题的表述很直接:现有机器人基础模型大多依赖大规模行为克隆,模仿专家动作,却丢弃了异构具身数据中可迁移的动力学知识。换句话说,机器人不应该只学习“高手怎么操作”,还应该学习“动作会如何改变世界”。这一区别非常关键。一个模型如果只记住抓取轨迹,在新物体、新背景、新位置下容易失效;如果它能理解接触、位移、遮挡、滑动、翻转等状态转移规律,就更可能在复杂任务中修正动作并处理长程误差。
2. LDA-1B 的基本思路
LDA-1B 的全称是 Latent Dynamics Action Model,可以理解为“在潜在空间里联合学习动力学和动作的模型”。它继承了统一世界模型的思想:同一个模型不仅要预测动作,还要预测未来视觉状态、根据前后状态反推动作,并在没有动作标注时进行视觉预测。论文把这些目标归纳为四类:策略学习、前向动力学、逆向动力学和视觉预测。这样设计以后,模型不再只回答“下一步怎么做”,还可以回答“如果这么做,画面中的物体会怎样变化”。
这四个训练目标在一个多模态扩散 Transformer 中共同优化。策略学习对应从当前观察和语言指令生成未来动作;前向动力学对应在给定动作后预测未来视觉表征;逆向动力学对应从前后视觉状态反推动作;视觉预测则不依赖动作标签,只根据当前观察推断未来状态。这个组合使 LDA-1B 能够利用不同监督强度的数据:专家机器人轨迹可以训练策略和动力学,噪声轨迹可以主要训练动力学,无动作人类视频可以训练视觉预测。数据的价值不再由“是否完美可模仿”决定,而由“它能监督哪一类能力”决定。
3. EI-30K:把数据先组织成可学习的形态
LDA-1B 背后的数据集叫 EI-30K,论文称其包含超过 30k 小时的具身交互轨迹,包括 8.03k 小时真实机器人数据、8.6k 小时仿真机器人数据、7.2k 小时带动作的人类演示,以及 10k 小时无动作标注的人类视频。这个数据规模本身并不是唯一重点,更重要的是它覆盖了真实与仿真、人类与机器人、高质量与低质量、有动作与无动作等多个维度。传统做法往往会把这些数据拆开处理,或者只取其中最干净的一部分;EI-30K 的目标则是把它们统一到同一训练语义下。
统一数据格式是这里的基础工程。论文说明 EI-30K 将数据转换为 LeRobot 格式,而 LeRobot 官方文档也将其描述为面向机器人学习数据的标准化格式,能够统一访问多模态时间序列、传感器运动信号、多相机视频以及元数据。对具身模型来说,格式统一不是琐碎细节,而是规模化训练的前提:如果每个数据集的视频、动作、时间戳、语言标注、相机参数都用不同方式存放,模型训练前的大量成本会消耗在数据清洗和适配上,而不是学习本身。
TRAINING_TASKS = ["policy", "forward_dynamics", "inverse_dynamics", "video_gen"]
VIDEOGEN_DATASET = ["egocentric_10k", "taste_rob", "rh20t"]
论文中把第四类任务称为 visual forecasting,代码中对应的任务名是 video_gen。在 get_vla_dataset 里,普通有动作数据进入 LeRobotSingleDataset;egocentric_10k、taste_rob、rh20t 这类无动作或视频预测数据进入 VideoTaskSingleDataset。如果混合数据里包含视频预测数据,函数会返回带动作数据集和全量数据集的组合;训练时实际用全量数据集,但每个样本会被任务采样器分配为 policy、forward_dynamics、inverse_dynamics 或 video_gen。这说明官方代码不是简单把所有数据混在一起,而是在 dataloader 层就把训练目标作为采样维度显式建模。
task_weights = cfg.datasets.vla_data.get(
"training_task_weights", [1.0] * len(TRAINING_TASKS)
)
sampler = DistributedTaskBatchSampler(
all_dataset,
batch_size=cfg.datasets.vla_data.per_device_batch_size,
tasks=TRAINING_TASKS,
task_weights=dict(zip(TRAINING_TASKS, task_weights)),
seed=cfg.seed,
drop_last=True,
)
DistributedTaskBatchSampler 是 LDA-1B 训练实现中很重要的一层。官方代码要求 batch_size >= len(tasks),并在每个 batch 中先放入四类任务各一个样本,再按照 training_task_weights 对剩余位置采样。这样做有两个效果:第一,保证 policy、forward dynamics、inverse dynamics、video_gen 不会因为数据量差异而长期缺席;第二,仍然允许通过权重调节任务比例。对于异构具身数据来说,这是比“随机混合数据集”更稳的做法,因为不同数据源天然对应不同监督信号,训练采样必须显式感知任务类型。
4. 动作空间如何跨本体对齐
多机器人、多灵巧手、多数据源训练的一个难点是动作含义不一致。双指夹爪的“闭合宽度”、22 自由度灵巧手的关节配置、人类手部 MANO 参数,在原始形式上并不能直接混合。LDA-1B 采用手部中心的动作表示,将机器人末端执行器或人类手腕统一到共享坐标系下。机器人侧通常表示为 6 自由度末端位姿加夹爪宽度或手指关节;人类侧则记录 6 自由度腕部位姿和 MANO 手部参数,并保留相机外参以消除第一视角头部运动带来的干扰。
这种坐标系对齐的意义在于,把“身体形态差异”尽量转化为“统一坐标系中的手部运动差异”。如果没有这一步,同样是“向右推杯子”,不同数据集里的动作向量可能代表完全不同的坐标方向、尺度或执行器状态,模型只能学到噪声。坐标对齐之后,人类操作视频、双指夹爪轨迹、灵巧手轨迹之间才有共享结构:手接近物体、接触物体、施加力、物体移动或翻转。这些才是机器人跨本体泛化时真正需要迁移的部分。
if self.use_delta_action:
raw_data = self.get_delta_action_from_raw_data(
raw_data, embodiment_tag, dataset.history_action_indices
)
for action_key in dataset.modality_keys["action"]:
padded_action, mask = pad_action_state_with_key(
data[action_key][history_len:], action_key, dataset_single_arm
)
action.append(padded_action)
action_mask.append(mask)
action = np.concatenate(action, axis=1).astype(np.float16)
action_mask = np.concatenate(action_mask, axis=1)
action, action_mask = pad_action_state_to_max_length(
action, action_mask, self.action_dim
)
上面这段是官方代码中真正进入训练 batch 前的动作处理路径,位置在 LeRobotMixtureDataset.__getitem__。它会读取当前样本的动作字段,根据 use_delta_action 决定是否调用 get_delta_action_from_raw_data,再逐个 action key 做 padding 和 mask 生成,最后把多个动作子字段拼接为统一长度的 action tensor。这里的 mask 很关键,因为不同本体并不一定拥有同样的动作维度;代码通过 pad_action_state_to_max_length 把它们补到全局 action_dim,同时用 action_mask 标记哪些维度真实有效。论文中“跨本体动作对齐”的几何标定和清洗细节并未在当前开源仓库中完整释放,但训练代码已经能看到统一动作向量、历史动作、mask 和 embodiment id 如何进入模型。
EMBODIMENT_TAG_MAPPING = {
EmbodimentTag.AGIBOT_GRIPPER.value: 0,
EmbodimentTag.Galaxea.value: 1,
EmbodimentTag.Droid.value: 2,
EmbodimentTag.Unitree.value: 3,
EmbodimentTag.FRANKA.value: 4,
EmbodimentTag.OXE.value: 5,
}
embodiment_id 不是装饰性字段,它会影响动作编码器和解码器的参数选择。官方 FlowmatchingActionHead 在 max_num_embodiments > 1 时启用 CategorySpecificMLP 和 MultiEmbodimentActionEncoder,为不同本体使用 category-specific 的线性层;当只有单一本体时,退化为普通 MLP 和普通 ActionEncoder。这相当于在共享 MM-DiT 主干之外,为不同机器人保留一层轻量本体适配能力:共享层学习通用视觉-动作动力学,本体相关层负责把统一隐空间映射到具体动作维度和执行器语义。
5. 为什么不用像素预测未来
传统世界模型常常尝试在像素空间预测未来画面,但像素级目标会把大量训练能力浪费在背景纹理、光照、相机噪声和无关细节上。机器人真正需要的不是把下一帧渲染得好看,而是理解杯子、抽屉、锤子、扫帚等对象在动作作用下如何变化。LDA-1B 因此选择在 DINOv3 的视觉潜空间中建模未来状态。DINOv3 官方资料强调其能够产生高质量 dense features,并在多类视觉任务上表现出较强通用性,这类特征更适合保留物体结构、空间关系和语义信息。
可以把 DINO 潜空间理解为“压缩后的视觉世界”。模型不再预测每个像素的颜色,而是预测图像块级别的语义与几何表征。这样做有两个直接好处:一是训练目标更接近机器人控制所需的物体级变化,二是减少光照和背景干扰对损失函数的支配。论文中的消融实验也支持这一点:在 RoboCasa-GR1 上,使用 VAE 视觉表征的 UWM 变体即使扩到 1B 参数,成功率仍明显低于使用 DINO 表征的 LDA;从 VAE 切换到 DINO 后,性能出现大幅提升。
if self.vision_encoder_type == "dinov3":
pretrained_model_name = os.path.join(
config.vision_encoder_path,
f"dinov3-vit{self.vision_encoder_size}16-pretrain-lvd1689m",
)
self.transform = AutoImageProcessor.from_pretrained(pretrained_model_name)
self.vision_encoder = DINOv3ViTModel.from_pretrained(
pretrained_model_name
).eval()
register_tokens = self.vision_encoder.config.num_register_tokens
self.glob_len = 1 + register_tokens
这段来自官方 FlowmatchingActionHead.__init__。代码中 vision_encoder_type 支持 dinov3、vjepa2 和 vae,其中 LDA-1B 主线使用 dinov3。加载后立即 .eval(),训练脚本默认冻结 action_model.vision_encoder,对应脚本中的 freeze_module_list='qwen_vl_interface,action_model.vision_encoder'。这意味着 DINOv3 在训练中主要作为固定特征抽取器:输入图像先经过 AutoImageProcessor 预处理,再由 DINOv3ViTModel 输出 last_hidden_state,后续动力学预测目标是在这些 token 上计算,而不是在 RGB 像素上计算。
def encode_future_img(self, next_obs, microbatch_size=72):
if self.vision_encoder_type == "dinov3":
next_obs = rearrange(next_obs, "b v t c h w -> (b v t) c h w")
transformed_imgs = []
for i in range(0, next_obs.shape[0], microbatch_size):
batch_next_obs = next_obs[i : i + microbatch_size]
with torch.no_grad():
output = self.vision_encoder(batch_next_obs)
batch_next_obs = output.last_hidden_state
transformed_imgs.append(batch_next_obs)
next_obs = torch.cat(transformed_imgs, dim=0)
return next_obs
encode_future_img 展示了官方实现为什么适合大 batch 训练:图像按 (batch, view, time) 展开为 (b v t) 后分 microbatch 送入视觉编码器,并且在 torch.no_grad() 中运行,避免对冻结视觉编码器保存梯度。对于 DINOv3,输出保留包含 cls/register/local patch token 的序列;后面代码会用 rearrange 将其恢复为 batch 维度,并通过 obs_merger 把当前观察和带噪未来观察在通道维拼接后映射到 MM-DiT 的输入维度。这个实现细节比“直接预测未来图片”更具体:LDA-1B 实际预测的是视觉 token 的 flow-matching velocity。
6. MM-DiT:让动作 token 和视觉 token 在同一模型里交互
LDA-1B 使用 Multi-Modal Diffusion Transformer,也就是 MM-DiT。开源仓库 README 中给出的结构信息包括:Qwen3-VL 作为语言和视觉语义编码器,DINOv3-ViT-S 作为视觉潜变量编码器,MM-DiT 主干为 16 层、hidden size 1536、32 个注意力头。模型输入包含当前观察、语言指令、扩散时间步、任务 embedding、动作 token 和未来视觉 token;输出则包括去噪后的动作块和未来视觉特征。仓库说明其单个 MMDiT backbone 会共同预测 DINOv3 token 和 16 步 action chunk。
qwen_inputs = self.qwen_vl_interface.build_qwenvl_inputs(
images=batch_images, instructions=instructions
)
qwenvl_outputs = self.qwen_vl_interface(
**qwen_inputs,
output_attentions=False,
output_hidden_states=True,
return_dict=True,
)
last_hidden = qwenvl_outputs.hidden_states[-1]
output_dict = self.action_model(
vl_embs=last_hidden_repeated,
actions=actions_target_repeated,
action_mask=actions_target_mask_repeated,
history_actions=history_actions_repeated,
state=state_repeated,
future_imgs=future_images_repeated,
curr_imgs=curr_images_repeated,
embodiment_id=embodiment_ids_repeated,
assigned_tasks=tasks,
encoder_attention_mask=attention_mask_repeated,
)
这是官方 QwenMMDiT.forward 的核心路径。框架先调用 qwen_vl_interface.build_qwenvl_inputs 把多视角图像和语言指令组织成 Qwen-VL 输入,再取 Qwen 输出的最后一层 hidden state 作为文本/视觉语义条件。随后才进入 action_model,也就是 MMDiT_ActionHeader.FlowmatchingActionHead。因此 LDA-1B 的动作头不是孤立的控制网络:它的扩散去噪过程始终被 Qwen-VL 的 token 条件化,语言指令和当前图像语义会通过 cross-attention 影响动作 token 与未来视觉 token。
image_tokens, action_tokens = self.joint_attn(inputs=(image_tokens, action_tokens))
image_tokens = self.img_cross_attn(
image_tokens,
encoder_hidden_states=text_tokens,
attention_mask=text_mask,
)
action_tokens = self.action_cross_attn(
action_tokens,
encoder_hidden_states=text_tokens,
attention_mask=text_mask,
)
MMDiTBlock 的结构比普通 Transformer 更有针对性。它先对 image tokens 和 action tokens 做 joint self-attention,让未来视觉表征和动作表征在同一注意力层里交换信息;然后分别对 image tokens、action tokens 做到 text tokens 的 cross-attention,把 Qwen-VL 的语义条件注入两条模态流;最后再分别进入 image FFN 和 action FFN。代码中两条流有各自的 layer norm、cross-attention、feed-forward 和残差函数,但共享 joint attention 的交互空间。这对应论文中“动作和视觉专家解耦,但通过共享自注意力交互”的设计。
if time_cond is not None:
time_cond = self.timestep_encoder(time_cond)
if task_embedding is not None:
time_cond += task_embedding
for block in self.blocks:
text_tokens, image_tokens, action_tokens = block(
time_cond=time_cond,
text_tokens=text_tokens,
image_tokens=image_tokens,
action_tokens=action_tokens,
text_mask=text_mask,
)
任务 embedding 的注入也能在官方代码里直接看到。MM-DiT 主干先用 TimestepEncoder 编码扩散时间步,再把 policy_embedding、fd_embedding、id_embedding 或 vg_embedding 加到同一个条件向量上。这个条件向量会进入每个 MMDiTBlock 的 adaptive conditioning 分支,生成 image/action 两条流在 attention 和 FFN 前后的 gamma、beta。也就是说,同一组网络参数会因为任务不同而处在不同的去噪模式:policy 模式关注动作速度场,forward dynamics 和 video_gen 模式关注未来视觉 token 速度场,inverse dynamics 模式则用未来视觉状态帮助反推动作。
7. 四任务在官方代码里如何构造损失
LDA-1B 最核心的训练逻辑在 MMDiT_ActionHeader.FlowmatchingActionHead.forward 中。官方实现会先把 batch 内样本按 assigned_tasks 分成四组:policy_indices、forward_dynamics_indices、inverse_dynamics_indices 和 video_gen_indices。随后 policy 和 inverse dynamics 组合成“需要预测动作”的集合,forward dynamics 和 video_gen 组合成“需要预测未来视觉”的集合。这个分组非常重要,因为它决定了哪些样本加动作噪声、哪些样本加视觉噪声,以及最终哪些损失会被计算。
pred_action_task_indices = policy_indices + inverse_dynamics_indices
pred_next_obs_task_indices = forward_dynamics_indices + video_gen_indices
to_noise_action = torch.cat((policy_action, inverse_action), dim=0)
act_t_sample = self.sample_time(
to_noise_action.shape[0], device=device, dtype=vl_embs.dtype
).reshape(-1)
action_noise = torch.randn_like(to_noise_action)
noisy_action = (1 - act_t_sample) * action_noise + act_t_sample * to_noise_action
action_velocity = to_noise_action - action_noise
这里采用的是 flow matching 风格的加噪方式。sample_time 从 Beta 分布采样连续时间,再把真实动作和高斯噪声线性插值得到 noisy_action;训练目标不是直接回归干净动作,而是回归从噪声到数据的速度 action_velocity = action - noise。对于策略学习,未来视觉位置用 learnable token 占位;对于逆向动力学,未来视觉使用真实 next obs token。也就是说,同样是预测动作,policy 和 inverse dynamics 给模型的条件不同:policy 只看当前状态和语言,inverse dynamics 额外看真实未来状态。
to_noise_next_obs = torch.cat((forward_obs, video_gen_obs), dim=0)
obs_t_sample = self.sample_time(
to_noise_next_obs.shape[0], device=device, dtype=vl_embs.dtype
).reshape(-1)
obs_noise = torch.randn_like(to_noise_next_obs)
noisy_obs = (1 - obs_t) * obs_noise + obs_t * to_noise_next_obs
obs_velocity = to_noise_next_obs - obs_noise
forward_act_feat = self.action_encoder(actions[forward_dynamics_indices], t_discretized_clean)
video_gen_act_feat = self.action_learnable_tokens.weight.unsqueeze(0).expand(
len(video_gen_indices), -1, -1
)
未来视觉分支也使用同样的速度场目标。forward dynamics 有真实动作,所以代码用 clean timestep 将真实动作编码为 forward_act_feat;video_gen 没有动作监督,所以使用 action_learnable_tokens 作为动作占位。这个实现与论文的“actionless human videos supervise visual forecasting”一致:无动作视频不参与动作模仿,但可以让模型学习从当前视觉状态到未来视觉 token 的时序变化。官方代码里没有把无动作视频伪造为机器人动作,而是用 learnable action token 明确表示该模态缺失。
policy_act_loss = F.mse_loss(
policy_pred_actions, action_velocity[:len(policy_indices)], reduction="none"
) * action_mask[policy_indices]
policy_act_loss = policy_act_loss.sum() / (action_mask[policy_indices].sum() + 1e-8)
inverse_act_loss = F.mse_loss(
inverse_pred_actions,
action_velocity[len(policy_indices):, :self.future_obs_index],
reduction="none",
) * action_mask[inverse_dynamics_indices, :self.future_obs_index]
pred_next_obs = self.get_next_obs_tokens(image_tokens, pred_next_obs_task_indices)
obs_loss = F.mse_loss(pred_next_obs, obs_velocity)
最终损失也按照任务分开计算。动作损失会乘 action_mask,避免 padding 出来的无效动作维度影响梯度;inverse dynamics 只取 future_obs_index 前的一段动作;视觉损失则在预测的 future DINO/VAE/VJEPA token 与 obs_velocity 之间计算 MSE。返回值中 loss 是总损失,action_loss 记录 policy action loss,dynamics_loss 记录视觉动力学损失。这个实现解释了为什么 LDA-1B 可以把不同质量的数据放在同一个 batch 里训练:每个样本的监督信号由任务类型和 mask 控制,而不是所有样本都强行走同一个行为克隆目标。
8. 推理时如何生成动作
训练时 LDA-1B 同时学习四类任务,但真实机器人执行时主要调用 policy 模式。官方 QwenMMDiT.predict_action 会先像训练一样构造 Qwen-VL 输入,取最后层 hidden state;然后调用 action head 的 predict_action。在 action head 内部,推理并不是简单前向一次输出动作,而是从标准高斯噪声初始化一段动作序列,再按照 num_inference_timesteps 做多步 Euler 积分。每一步都把当前带噪动作编码成 action tokens,把当前图像编码成 DINO tokens,并使用 policy task embedding 调用 MM-DiT 预测动作速度。
actions = torch.randn(
size=(B, self.config.action_horizon, self.config.action_dim),
dtype=vl_embs.dtype,
device=device,
)
task_embedding = self.policy_embedding.unsqueeze(0).expand(B, -1)
num_steps = self.num_inference_timesteps
dt = 1.0 / num_steps
for step in range(num_steps):
t_cont = step / float(num_steps)
t_discretized = int(t_cont * self.num_timestep_buckets)
timesteps = torch.full((B,), t_discretized, device=device, dtype=torch.long)
action_features = self.action_encoder(actions, timesteps)
_, action_tokens = self.model(
image_tokens=obs_tokens,
action_tokens=action_features,
text_tokens=vl_embs,
register_tokens=register_tokens,
text_mask=attention_mask,
time_cond=timesteps,
task_embedding=task_embedding,
)
pred_velocity = self.action_decoder(action_tokens)[:, -actions.shape[1] :]
actions = actions + dt * pred_velocity
这段官方代码说明了 LDA-1B 的动作输出为什么是“扩散/流匹配式动作块”。它生成的是 action_horizon 长度的 action chunk,而不是单步控制量;训练脚本中常见配置是 future_action_window_size=15,因此 action_horizon=16。推理循环结束后,QwenMMDiT.predict_action 将张量转回 numpy,并返回 normalized_actions。在 RoboCasa 闭环评估中,仿真环境会按 n_action_steps 执行其中一段动作,再把新观察送回模型服务。这种 chunk policy 可以降低每帧都调用大模型的频率,同时保留扩散模型对连续动作轨迹的建模能力。
9. 从代码仓库看复现流程
开源仓库给出的流程比较清晰:先创建 Python 3.10 环境,安装依赖、FlashAttention2 和本地包;再下载 Qwen3-VL-4B-Instruct 与 DINOv3-ViT-S 权重;训练时需要配置 base_vlm、vision_encoder_path、data_root_dir、data_mix、run_root_dir 和 run_id 等参数。仓库还提供了 RoboCasa-GR1 tabletop 任务的训练与评估说明,并包含一个 demo dataset 用于快速调试。需要注意的是,仓库 README 的 TODO 中仍列出预训练权重、预训练数据和数据预处理脚本等计划项,实际复现完整预训练还依赖更大规模数据资源。
conda create -n LDA python=3.10
conda activate LDA
pip install -r requirements.txt
pip install flash-attn --no-build-isolation
pip install -e .
# 微调 RoboCasa-GR1 数据集,需先在脚本中配置权重和数据路径
bash scripts/run_scripts/Robocasa/run_lerobot_datasets_LDA.sh
# 离线 open-loop 评估,根据数据集动作标签比较预测动作误差
bash scripts/eval_scripts/eval_lerobot_datasets_LDA.sh
如果要做闭环仿真评估,仓库示例使用两个进程:一个在 LDA 环境中启动 policy server,另一个在 RoboCasa 环境中启动仿真。这样的分离方式符合机器人评估的常见工程实践:模型服务负责根据观察输出动作,仿真环境负责执行动作并返回下一帧观察。闭环评估比 open-loop 更严格,因为错误动作会影响后续状态,模型必须在自己的分布偏移中继续控制,而不是只在离线数据帧上预测一次动作。
python deployment/model_server/server_policy.py \
--ckpt_path /path/to/your_ckpt \
--port 5678 \
--use_bf16
python examples/Robocasa_tabletop/eval_files/simulation_env.py \
--args.env_name ${env_name} \
--args.port 5678 \
--args.n_episodes 50 \
--args.max_episode_steps 720 \
--args.n_action_steps 12 \
--args.video_out_path ${video_out_path} \
--args.pretrained_path /path/to/your_ckpt
10. 结语
LDA-1B 的意义不在于提出一个更大的机器人模型,而在于给出了具身智能 scaling 的一条清晰路径:不要只等待昂贵的专家数据,也不要把低质量和无动作数据简单丢弃;应当先识别不同数据能监督什么,再把它们组织进统一的世界-动作模型。它把“数据筛选”推进到“数据分工”,把“模仿动作”推进到“理解动作后果”。如果这条路线继续发展,机器人基础模型的进步将不再只取决于专家遥操作采集速度,而会越来越依赖对真实世界异构经验的系统性吸收能力。
144