跳转到内容

规模化数据生成

在本章节中,我们将介绍如何使用 GenManip 进行规模化数据生成。本章节需要结合 高级数据生成 章节一起阅读,并本质上为 高级数据生成 章节提供一个具体的应用场景。

为了进行规模化的数据生成,你需要下载一些资产。你可以通过以下命令下载资产:

Terminal window
python standalone_tools/download_assets.py --dataset objaverse-subset

你可以参照 Object Annotation 章节对于你的物体进行标注并且保存为 pickle 文件。对于上述资产,我们已经进行了提前的标注,并且已经在 Codebase 中,你可以直接使用。对于你自己的标注,需要同样保存在 assets/objects 文件夹中。

对于规模化生成,我们需要尽可能多的随机化,并且在尽可能多的物体上进行随机生成 Pick and Place 数据。

接下来我们将依次讲解配置文件的设计。

首先,对于随机化,我们使用:

domain_randomization:
cameras:
config_path: configs/cameras/fixed_camera_robotiq_s2r_3L_align_twoObs.yml
type: fixed
object_data_path: objaverse_annotation_refined_pnp
random_environment:
has_wall: true
hdr: true
robot_base_position:
random_range: 0.05
robot_eepose: false
table_texture: true
table_type: true
wall_texture: true
rewrite_instruction: true

即设置相机文件为标定的相机配置文件,同时使用 objaverse_annotation_refined_pnp.pickle 文件中的物体标注信息。对于域随机化本身,我们启用了墙面、HDR(Dome light)、机器人基座位置随机化,以及桌面的纹理和类型随机化。同时我们启用了重写 instruction,即在生成数据时,会根据抓取以及放置的物体的标注信息,自动重写 instruction。

对于物体配置,使用:

object_config:
background_0: &id003
clip_range:
max: 0.2
min: 0.05
filter_rule: []
max_cached_num: 30
is_not_rigid: true
path: object_usds/objaverse_usd
type: load_object_from_path
background_1: *id003
background_2: *id003
background_3: *id003
background_4: *id003
background_5: *id003
background_6: *id003
background_7: *id003
background_8: *id003
obj1_0:
clip_range:
max: 0.15
min: 0.05
filter_rule:
- can_grasp
max_cached_num: 30
option:
- adjust_thickness
path: object_usds/objaverse_usd
type: load_object_from_path
obj2:
clip_range:
max: 0.35
min: 0.2
filter_rule:
- is_container
max_cached_num: 30
option:
- force_top
path: object_usds/objaverse_usd
type: load_object_from_path

可以看到其中引入了 11 个物体,其中 9 个背景物体,2 个目标物体。对于全部物体,我们使用了 load_object_from_path 类型,并且从 object_usds/objaverse_usd 文件夹中加载物体。对于背景物体,我们设置了 is_not_rigid,使得在加载之后物体不可受到力的作用而改变位置。对于三种不同的物体,我们设置了不同的 clip_range,最后的物体尺寸将在标注尺寸和 clip_range 的交集中随机采样。对于每种物体,都会预加载 30 个物体,而不会加载更多以防内存占用过高。

对于 obj1 以及 obj2,他们必须在标注中被标注为可以抓取(can_grasp)以及是容器(is_container)。同时,obj1 被设置为 adjust_thickness,即在加载之后,物体厚度会被调整至小于夹爪宽度。force_top 是一个过时的选项,现在已经被弃用。

在设置了物体之后,我们还需要设置布局:

layout_config:
ignored_objects: []
type: random_custom_tableset
in_order: true
custom_tableset:
obj1_0: &id001
type: global_range
random_range_angle: 360
random_range_h: 0.7
random_range_w: 0.4
random_range_x: -0.2
random_range_y: -0.35
obj2: *id001
background_0: &id002
type: global_range
random_range_angle: 360
random_range_h: 20
random_range_w: 20
random_range_x: -10
random_range_y: -10
background_1: *id002
background_2: *id002
background_3: *id002
background_4: *id002
background_5: *id002
background_6: *id002
background_7: *id002
background_8: *id002

可以看到我们均使用 random_custom_tableset 类型,并且按照 custom_tableset 中的顺序依次放置每一个物体(in_order: true)。对于每个物体,我们使用 global_range 类型。对于 obj1 以及 obj2,我们期望将物体放置在机器人的动作空间内,如上设置。对于背景物体,他们只需要被放置在桌面上即可,因此设置为一个过大的范围,程序会自动将范围调整到范围与桌面的交集。

generation_config:
reset_tcp: true
action_path:
mode: auto
robot: 0
articulation: []
goal:
- - obj1_uid:
- obj1_0
obj2_uid:
- obj2
position:
- top
fixed_position: true
mode: random_all
planner: curobo
instruction: ''

接下里我们设置生成相关配置,任务为将 obj1 放置在 obj2 的顶部,并且使用 curobo 作为规划器。在这里我们设置 instruction 为空,因为 instruction 会在重写阶段自动生成。

接下来还包括设置一系列配置文件:

mode: manual
num_episode: 1000000
restart_per_success: 100
preprocess_config:
- config:
config: default
type: convexDecomposition
type: collider
robots:
- config:
gripper_type: robotiq
default_joint_positions:
- 0.0
- -0.785
- 0.0
- -2.356
- 0.0
- 1.57079
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
type: franka
table_uid: aa49db8a801d402dac6cf1579536502c
task_name: system1_scaling_14kobj_object_container_fgrandpos_bgrandpos_fgclip_NOrobotbaserandpos_bgcache10_bgclip_3L2obsAlign_refineActionSpace
usd_name: scene_usds/sim2real_scenes_align_for_scaling/base

在这里使用 RoboTiq 作为夹爪,程序每成功生成 100 个数据后,会重新进行预加载物体流程,以确保单一程序也可以具有多样性,而不是仅在预加载的 90 个物体上进行生成。其余内容并无特殊之处。

完整的配置文件在 Codebase 中可以找到,你可以直接使用。

Terminal window
# 确保你启动了 AnyGrasp 服务
python demogen.py -cfg configs/tasks/scaling_up/system1_scaling_14kobj_object_container_fgrandpos_bgrandpos_fgclip_NOrobotbaserandpos_bgcache10_bgclip_3L2obsAlign_refineActionSpace.yml
python render.py -cfg configs/tasks/scaling_up/system1_scaling_14kobj_object_container_fgrandpos_bgrandpos_fgclip_NOrobotbaserandpos_bgcache10_bgclip_3L2obsAlign_refineActionSpace.yml

如果你需要使用你自己的资产,那么就进行标注,然后将物体配置中的文件夹路径替换为你的资产路径即可。