File size: 3,772 Bytes
393dd2a
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
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
# Absolute path to URDF
urdf_path: fetch_source.urdf                      # (str) Absolute path to robot URDF to import
name: fetch                           # (str) Name to assign to robot
headless: false                          # (bool) if set, run without GUI
overwrite: true                         # (bool) if set, overwrite any existing files
merge_fixed_joints: true
base_motion:
  wheel_links:                      # (list of str): links corresponding to wheels
    - l_wheel_link
    - r_wheel_link
  wheel_joints:                     # (list of str): joints corresponding to wheel motion
    - l_wheel_joint
    - r_wheel_joint
  use_sphere_wheels: true           # (bool) whether to use sphere approximation for wheels (better stability)
  use_holonomic_joints: false       # (bool) whether to use joints to approximate a holonomic base. In this case, all
                                    #       wheel-related joints will be made into fixed joints, and 6 additional
                                    #       "virtual" joints will be added to the robot's base capturing 6DOF movement,
                                    #       with the (x,y,rz) joints being controllable by motors
collision:
  decompose_method: coacd                  # (str) [coacd, convex, or null] collision decomposition method
  hull_count: 8                     # (int) per-mesh max hull count to use during decomposition, only relevant for coacd
  coacd_links: []                   # (list of str): links that should use CoACD to decompose collision meshes
  convex_links:                     # (list of str): links that should use convex hull of visual meshes to decompose collision meshes
    - base_link
    - torso_fixed_link
    - head_pan_link
    - head_tilt_link
    - wrist_roll_link
    - gripper_link
  no_decompose_links:               # (list of str): links that should not have any post-processing done to them
    - l_wheel_link
    - r_wheel_link
    - l_gripper_finger_link
    - r_gripper_finger_link
  no_collision_links:               # (list of str) links that will have any associated collision meshes removed
    - laser_link
    - estop_link
eef_vis_links:                      # (list of dict) information for adding cameras to robot
  - link: eef_link                  # same format as @camera_links
    parent_link: wrist_roll_link
    offset:
      position: [0.16645, 0, 0]
      orientation: [0.707, 0, 0.707, 0]
camera_links:                       # (list of dict) information for adding cameras to robot
  - link: eyes                      # (str) link name to add camera. Must exist if @parent_link is null, else will be
                                    #       added as a child of the parent
    parent_link: head_tilt_link               # (str) optional parent link to use if adding new link
    offset:                         # (dict) local pos,ori offset values. if @parent_link is specified, defines offset
                                    #       between @parent_link and @link specified in @parent_link's frame.
                                    #       Otherwise, specifies offset of generated prim relative to @link's frame
      position: [0.055, 0, 0.0225]           # (3-tuple) (x,y,z) offset -- this is done BEFORE the rotation
      orientation: [0.5, -0.5, -0.5, 0.5]   # (4-tuple) (x,y,z,w) offset
  - link: eef_link
    parent_link: null
    offset:
      position: [0.05, 0, -0.05]
      orientation: [-0.7011, -0.7011, -0.0923, -0.0923]
lidar_links:                        # (list of dict) information for adding cameras to robot
  - link: laser_link                # same format as @camera_links
    parent_link: base_link
    offset:
      position: [0.235, 0, 0.2878]
      orientation: [1.0, 0, 0, 0]
curobo: null