| """ |
| Stage 6: Physics-based pose refinement. |
| |
| Given an estimated pose from Stage 5, sample poses around it and validate |
| using physics simulation. A pose is valid if: |
| 1. No collision with container at initial placement |
| 2. Position doesn't change much after physics settling |
| 3. Rotation doesn't change much after physics settling |
| """ |
|
|
| import json |
| import os |
| from dataclasses import dataclass |
| from typing import List, Optional, Tuple |
|
|
| import numpy as np |
| import torch |
| from scipy.spatial.transform import Rotation as R |
|
|
| import genesis as gs |
| import genesis.utils.geom as gu |
| import genesis_patch |
|
|
|
|
| @dataclass |
| class PhysicsRefineArgs: |
| """Configuration for physics-based pose refinement.""" |
| output_dir: str |
| object_mesh_path: str |
| container_mesh_path: str |
| table_path: str = "../video_gen_assets/table.glb" |
|
|
| |
| table_pos: Tuple[float, float, float] = (0.0, 0.0, 0.485403) |
| table_euler: Tuple[float, float, float] = (90.0, 0.0, 90.0) |
| table_height: float = 0.7451 |
| container_euler: Tuple[float, float, float] = (90.0, 0.0, 0.0) |
| container_pos: Optional[Tuple[float, float, float]] = None |
| container_scale: float = 1.0 |
| object_scale: float = 1.0 |
|
|
| |
| num_samples: int = 64 |
| xy_jitter: float = 0.02 |
| z_jitter: float = 0.01 |
| xyz_jitter: Tuple[float, float, float] = None |
| rot_jitter_deg: Tuple[float, float, float] = (5.0, 5.0, 15.0) |
|
|
| |
| physics_steps: int = 300 |
| dt: float = 0.01 |
|
|
| |
| max_pos_drift: float = 0.03 |
| max_rot_drift_deg: float = 15.0 |
|
|
| |
| use_parallel: bool = True |
|
|
| |
| wall_mode: bool = False |
| wall_x: float = -0.5 |
| wall_height: float = 1.2 |
|
|
| |
| coacd_threshold: float = 0.01 |
| coacd_resolution: int = 80 |
| max_convex_hull: int = 20 |
|
|
| |
| num_rounds: int = 1 |
|
|
| |
| render_initial: bool = False |
|
|
|
|
| def jitter_pos(pos: np.ndarray, xy_jitter: float = 0.02, z_jitter: float = 0.01, |
| xyz_jitter: Tuple[float, float, float] = None) -> np.ndarray: |
| """Add small uniform noise to position. If xyz_jitter is given, use per-axis values.""" |
| pos = np.array(pos, dtype=np.float32).copy() |
| if xyz_jitter is not None: |
| for i in range(3): |
| pos[i] += np.random.uniform(-xyz_jitter[i], xyz_jitter[i]) |
| else: |
| pos[:2] += np.random.uniform(-xy_jitter, xy_jitter, size=2) |
| pos[2] += np.random.uniform(-z_jitter, z_jitter) |
| return pos |
|
|
|
|
| def jitter_rot(euler_deg: np.ndarray, jitter_deg: Tuple[float, float, float] = (5, 5, 15)) -> np.ndarray: |
| """Add small uniform noise to each Euler angle (degrees).""" |
| euler_deg = np.array(euler_deg, dtype=np.float32).copy() |
| jitter = np.array(jitter_deg) |
| euler_deg += np.random.uniform(-jitter, jitter) |
| return euler_deg |
|
|
|
|
| def rotvec_to_euler_deg(rotvec: np.ndarray) -> np.ndarray: |
| """Convert rotation vector to Euler angles in degrees.""" |
| rot = R.from_rotvec(rotvec) |
| return rot.as_euler('xyz', degrees=True) |
|
|
|
|
| def euler_deg_to_quat_wxyz(euler_deg: np.ndarray) -> np.ndarray: |
| """Convert Euler angles (degrees) to quaternion (w, x, y, z).""" |
| rot = R.from_euler('xyz', euler_deg, degrees=True) |
| quat_xyzw = rot.as_quat() |
| return np.array([quat_xyzw[3], quat_xyzw[0], quat_xyzw[1], quat_xyzw[2]]) |
|
|
|
|
| def compute_rotation_diff_deg(quat1_wxyz: np.ndarray, quat2_wxyz: np.ndarray) -> float: |
| """Compute rotation difference in degrees between two quaternions.""" |
| |
| q1_xyzw = np.array([quat1_wxyz[1], quat1_wxyz[2], quat1_wxyz[3], quat1_wxyz[0]]) |
| q2_xyzw = np.array([quat2_wxyz[1], quat2_wxyz[2], quat2_wxyz[3], quat2_wxyz[0]]) |
|
|
| r1 = R.from_quat(q1_xyzw) |
| r2 = R.from_quat(q2_xyzw) |
|
|
| |
| r_diff = r1.inv() * r2 |
| angle_rad = r_diff.magnitude() |
| return np.degrees(angle_rad) |
|
|
|
|
| def _load_estimated_pose(args: PhysicsRefineArgs): |
| """Load estimated pose from Stage 5 results.""" |
| pose_path = os.path.join(args.output_dir, "pose_estimation", "best_pose.json") |
| with open(pose_path, "r") as f: |
| pose_data = json.load(f) |
|
|
| if "tvec_w_icp" in pose_data: |
| tvec_w = np.array(pose_data["tvec_w_icp"]) |
| rvec_w = np.array(pose_data["rvec_w_icp"]) |
| print("Using ICP-refined pose as starting point") |
| else: |
| tvec_w = np.array(pose_data["tvec_w"]) |
| rvec_w = np.array(pose_data["rvec_w"]) |
| print("Using 3D-3D registration pose as starting point") |
|
|
| print(f"Starting position: {tvec_w}") |
| print(f"Starting rotation (rotvec): {rvec_w}") |
| euler_deg = rotvec_to_euler_deg(rvec_w) |
| return tvec_w, rvec_w, euler_deg |
|
|
|
|
| def _build_scene(args: PhysicsRefineArgs, tvec_w, euler_deg): |
| """Build Genesis scene for physics refinement (table or wall mode).""" |
| import trimesh |
| from trimesh.transformations import euler_matrix |
|
|
| gs.init(seed=0, precision="32", logging_level="warning") |
| genesis_patch.apply() |
|
|
| |
| renderer_kwargs = {} |
| if args.render_initial: |
| renderer_kwargs["renderer"] = gs.renderers.Rasterizer() |
|
|
| scene = gs.Scene( |
| sim_options=gs.options.SimOptions(dt=args.dt, substeps=5), |
| show_viewer=False, |
| rigid_options=gs.options.RigidOptions( |
| enable_collision=True, |
| enable_self_collision=False, |
| ), |
| **renderer_kwargs, |
| ) |
|
|
| mat_convex = gs.materials.Rigid() |
| mat_target = gs.materials.Rigid(friction=3.0) |
| wall = None |
|
|
| coacd_opts = gs.options.CoacdOptions( |
| threshold=args.coacd_threshold, |
| preprocess_resolution=args.coacd_resolution, |
| decimate=True, |
| max_convex_hull=args.max_convex_hull, |
| ) |
|
|
| if args.wall_mode: |
| |
| from place_scene import add_wall, DEFAULT_WALL_TEXTURE |
| c_euler = list(args.container_euler) |
|
|
| |
| wall_thickness = 0.05 |
| wall = scene.add_entity( |
| material=gs.materials.Rigid(sdf_min_res=16, sdf_max_res=16), |
| morph=gs.morphs.Box( |
| pos=[args.wall_x - wall_thickness / 2, 0.0, 1.5], |
| size=[wall_thickness, 3.0, 3.0], |
| collision=True, |
| fixed=True, |
| ), |
| ) |
|
|
| |
| crx, cry, crz = np.deg2rad(c_euler) |
| cmesh = trimesh.load(args.container_mesh_path, force="mesh") |
| cmesh.apply_transform(euler_matrix(crx, cry, crz, "sxyz")) |
| min_x = cmesh.bounds[0][0] |
| container_x = args.wall_x - min_x |
| container_pos = [container_x, 0.0, args.wall_height] |
| print(f"Container placed on wall at pos={container_pos}") |
|
|
| container = scene.add_entity( |
| material=mat_convex, |
| morph=gs.morphs.Mesh( |
| file=args.container_mesh_path, |
| pos=container_pos, |
| euler=c_euler, |
| scale=args.container_scale, |
| collision=True, |
| fixed=True, |
| convexify=True, |
| merge_submeshes_for_collision=False, |
| group_by_material=False, |
| coacd_options=coacd_opts, |
| ), |
| vis_mode="collision", |
| ) |
| else: |
| |
| mat_sdf_lo = gs.materials.Rigid(sdf_min_res=16, sdf_max_res=16) |
| c_euler = list(args.container_euler) |
|
|
| scene.add_entity( |
| material=mat_sdf_lo, |
| morph=gs.morphs.Mesh( |
| file=args.table_path, |
| pos=list(args.table_pos), |
| euler=list(args.table_euler), |
| collision=True, |
| fixed=True, |
| convexify=True, |
| ), |
| ) |
|
|
| if args.container_pos is not None: |
| container_pos = list(args.container_pos) |
| print(f"Container placed at pos={container_pos} (override)") |
| else: |
| crx, cry, crz = np.deg2rad(c_euler) |
| cmesh = trimesh.load(args.container_mesh_path, force="mesh") |
| cmesh.apply_transform(euler_matrix(crx, cry, crz, "sxyz")) |
| container_z = args.table_height - cmesh.bounds[0][2] |
| container_pos = [0.0, 0.0, container_z] |
| print(f"Container auto-placed at z={container_z:.4f}") |
|
|
| container = scene.add_entity( |
| material=mat_convex, |
| morph=gs.morphs.Mesh( |
| file=args.container_mesh_path, |
| pos=container_pos, |
| euler=c_euler, |
| scale=args.container_scale, |
| collision=True, |
| fixed=True, |
| convexify=True, |
| merge_submeshes_for_collision=False, |
| group_by_material=False, |
| coacd_options=coacd_opts, |
| ), |
| vis_mode="collision", |
| ) |
|
|
| |
| target_mesh_kwargs = { |
| "file": args.object_mesh_path, |
| "pos": list(tvec_w), |
| "euler": list(euler_deg), |
| "collision": True, |
| "fixed": False, |
| "coacd_options": coacd_opts, |
| } |
| if args.object_scale != 1.0: |
| target_mesh_kwargs["scale"] = args.object_scale |
| target = scene.add_entity( |
| material=mat_target, |
| morph=gs.morphs.Mesh(**target_mesh_kwargs), |
| vis_mode="collision", |
| ) |
| for link in target.links: |
| link._inertial_mass = 0.05 |
|
|
| |
| cam = None |
| if args.render_initial: |
| cam_pose_path = os.path.join(args.output_dir, "cam_pose.npy") |
| if os.path.exists(cam_pose_path): |
| cam_pose_mat = np.load(cam_pose_path) |
| cam_pos = cam_pose_mat[:3, 3] |
| forward = cam_pose_mat[:3, 2] |
| lookat = cam_pos + forward * 1.0 |
| cam = scene.add_camera( |
| pos=tuple(cam_pos), |
| lookat=tuple(lookat), |
| res=(1200, 896), |
| fov=50.0, |
| GUI=False, |
| ) |
| else: |
| print("WARNING: cam_pose.npy not found, skipping render") |
|
|
| return scene, container, target, wall, cam |
|
|
|
|
| def _render_initial_pose(args: PhysicsRefineArgs, cam): |
| """Render the initial pose with collision meshes for debugging.""" |
| import imageio |
|
|
| if cam is None: |
| return |
|
|
| img = cam.render()[0] |
|
|
| out_dir = os.path.join(args.output_dir, "physics_refinement") |
| os.makedirs(out_dir, exist_ok=True) |
| out_path = os.path.join(out_dir, "initial_pose_collision_mesh.png") |
| imageio.imwrite(out_path, img) |
| print(f"Rendered initial pose with collision meshes: {out_path}") |
|
|
|
|
| def refine_pose_physics_sequential(args: PhysicsRefineArgs) -> List[dict]: |
| """ |
| Refine pose using sequential physics simulation. |
| Simpler but slower than parallel version. |
| """ |
| print("=" * 60) |
| print("Physics-based Pose Refinement (Sequential)") |
| print("=" * 60) |
|
|
| tvec_w, rvec_w, euler_deg = _load_estimated_pose(args) |
| scene, container, target, wall_ent, _ = _build_scene(args, tvec_w, euler_deg) |
| scene.build() |
|
|
| |
| valid_poses = [] |
| print(f"\nSampling {args.num_samples} poses around estimated position...") |
|
|
| for i in range(args.num_samples): |
| |
| sampled_pos = jitter_pos(tvec_w, args.xy_jitter, args.z_jitter, xyz_jitter=args.xyz_jitter) |
| sampled_euler = jitter_rot(euler_deg, args.rot_jitter_deg) |
| sampled_quat = euler_deg_to_quat_wxyz(sampled_euler) |
|
|
| |
| scene.reset() |
| target.set_pos(torch.tensor(sampled_pos, dtype=torch.float32)) |
| target.set_quat(torch.tensor(sampled_quat, dtype=torch.float32)) |
|
|
| |
| init_pos = target.get_pos().cpu().numpy() |
| init_quat = target.get_quat().cpu().numpy() |
|
|
| |
| for _ in range(args.physics_steps): |
| scene.step() |
|
|
| |
| final_pos = target.get_pos().cpu().numpy() |
| final_quat = target.get_quat().cpu().numpy() |
|
|
| |
| pos_drift = np.linalg.norm(final_pos - init_pos) |
| rot_drift = compute_rotation_diff_deg(init_quat, final_quat) |
|
|
| |
| is_valid = (pos_drift < args.max_pos_drift) and (rot_drift < args.max_rot_drift_deg) |
|
|
| if is_valid: |
| valid_poses.append({ |
| "pos": final_pos.tolist(), |
| "quat_wxyz": final_quat.tolist(), |
| "euler_deg": rotvec_to_euler_deg(R.from_quat( |
| [final_quat[1], final_quat[2], final_quat[3], final_quat[0]] |
| ).as_rotvec()).tolist(), |
| "pos_drift": float(pos_drift), |
| "rot_drift_deg": float(rot_drift), |
| "sample_idx": i, |
| }) |
| print(f" Sample {i}: VALID (pos_drift={pos_drift:.4f}m, rot_drift={rot_drift:.2f}°)") |
| else: |
| if i < 10: |
| print(f" Sample {i}: invalid (pos_drift={pos_drift:.4f}m, rot_drift={rot_drift:.2f}°)") |
|
|
| print(f"\nFound {len(valid_poses)} valid poses out of {args.num_samples} samples") |
|
|
| return valid_poses |
|
|
|
|
| def refine_pose_physics_parallel(args: PhysicsRefineArgs) -> List[dict]: |
| """ |
| Refine pose using parallel physics simulation with batched environments. |
| Supports multiple rounds of sampling. |
| """ |
| print("=" * 60) |
| print("Physics-based Pose Refinement (Parallel)") |
| print("=" * 60) |
|
|
| tvec_w, rvec_w, euler_deg = _load_estimated_pose(args) |
|
|
| n_envs = args.num_samples |
| scene, container, target, wall_ent, cam = _build_scene(args, tvec_w, euler_deg) |
|
|
| |
| scene.build(n_envs=n_envs) |
|
|
| |
| if args.render_initial: |
| _render_initial_pose(args, cam) |
|
|
| all_valid_poses = [] |
| total_samples = 0 |
| total_collisions = 0 |
|
|
| for round_idx in range(args.num_rounds): |
| if args.num_rounds > 1: |
| print(f"\n--- Round {round_idx + 1}/{args.num_rounds} ---") |
|
|
| |
| sampled_positions = np.zeros((n_envs, 3), dtype=np.float32) |
| sampled_quats = np.zeros((n_envs, 4), dtype=np.float32) |
|
|
| for i in range(n_envs): |
| if round_idx == 0 and i == 0: |
| |
| sampled_pos = np.array(tvec_w, dtype=np.float32) |
| sampled_quat = euler_deg_to_quat_wxyz(euler_deg) |
| else: |
| sampled_pos = jitter_pos(tvec_w, args.xy_jitter, args.z_jitter, xyz_jitter=args.xyz_jitter) |
| sampled_euler = jitter_rot(euler_deg, args.rot_jitter_deg) |
| sampled_quat = euler_deg_to_quat_wxyz(sampled_euler) |
| sampled_positions[i] = sampled_pos |
| sampled_quats[i] = sampled_quat |
|
|
| print(f"\nRunning {n_envs} parallel simulations...") |
|
|
| |
| scene.reset() |
|
|
| |
| target.set_pos(torch.tensor(sampled_positions, dtype=torch.float32, device="cuda")) |
| target.set_quat(torch.tensor(sampled_quats, dtype=torch.float32, device="cuda")) |
|
|
| |
| collided = target.detect_collision_parallel(with_entity=container) |
| if wall_ent is not None: |
| collided_wall = target.detect_collision_parallel(with_entity=wall_ent) |
| collided = collided | collided_wall |
| n_colliding = int(collided.sum()) |
| total_collisions += n_colliding |
| total_samples += n_envs |
| print(f" Initial collision: {n_colliding}/{n_envs} envs") |
|
|
| |
| init_pos = target.get_pos().cpu().numpy() |
| init_quat = target.get_quat().cpu().numpy() |
|
|
| |
| for step in range(args.physics_steps): |
| scene.step() |
| if (step + 1) % 30 == 0: |
| print(f" Step {step + 1}/{args.physics_steps}") |
|
|
| |
| final_pos = target.get_pos().cpu().numpy() |
| final_quat = target.get_quat().cpu().numpy() |
|
|
| |
| round_valid = 0 |
| for i in range(n_envs): |
| if collided[i]: |
| continue |
|
|
| pos_drift = np.linalg.norm(final_pos[i] - init_pos[i]) |
| rot_drift = compute_rotation_diff_deg(init_quat[i], final_quat[i]) |
| is_valid = (pos_drift < args.max_pos_drift) and (rot_drift < args.max_rot_drift_deg) |
|
|
| if is_valid: |
| quat_xyzw = [final_quat[i][1], final_quat[i][2], final_quat[i][3], final_quat[i][0]] |
| final_euler = R.from_quat(quat_xyzw).as_euler('xyz', degrees=True) |
| init_quat_xyzw = [init_quat[i][1], init_quat[i][2], init_quat[i][3], init_quat[i][0]] |
| init_euler = R.from_quat(init_quat_xyzw).as_euler('xyz', degrees=True) |
|
|
| all_valid_poses.append({ |
| "pos": final_pos[i].tolist(), |
| "quat_wxyz": final_quat[i].tolist(), |
| "euler_deg": final_euler.tolist(), |
| "init_pos": init_pos[i].tolist(), |
| "init_quat_wxyz": init_quat[i].tolist(), |
| "init_euler_deg": init_euler.tolist(), |
| "pos_drift": float(pos_drift), |
| "rot_drift_deg": float(rot_drift), |
| "sample_idx": round_idx * n_envs + i, |
| "round": round_idx, |
| }) |
| round_valid += 1 |
|
|
| print(f" Round {round_idx + 1}: {round_valid} valid poses") |
|
|
| print(f"\nTotal: {len(all_valid_poses)} valid poses out of {total_samples} samples " |
| f"({total_collisions} initial collisions)") |
|
|
| |
| all_valid_poses.sort(key=lambda x: x["pos_drift"] + x["rot_drift_deg"] / 100) |
|
|
| return all_valid_poses |
|
|
|
|
| def refine_pose_physics(args: PhysicsRefineArgs) -> dict: |
| """ |
| Main entry point for physics-based pose refinement. |
| |
| Returns dict with best refined pose and all valid poses. |
| """ |
| if args.use_parallel: |
| valid_poses = refine_pose_physics_parallel(args) |
| else: |
| valid_poses = refine_pose_physics_sequential(args) |
|
|
| |
| refine_dir = os.path.join(args.output_dir, "physics_refinement") |
| os.makedirs(refine_dir, exist_ok=True) |
|
|
| total_samples = args.num_samples * args.num_rounds |
| results = { |
| "num_samples": total_samples, |
| "num_rounds": args.num_rounds, |
| "num_valid": len(valid_poses), |
| "valid_poses": valid_poses, |
| "best_pose": valid_poses[0] if valid_poses else None, |
| } |
|
|
| results_path = os.path.join(refine_dir, "refined_poses.json") |
| with open(results_path, "w") as f: |
| json.dump(results, f, indent=2) |
| print(f"\nSaved results to: {results_path}") |
|
|
| if valid_poses: |
| best = valid_poses[0] |
| print(f"\nBest refined pose:") |
| print(f" Position: {best['pos']}") |
| print(f" Rotation (euler): {best['euler_deg']}") |
| print(f" Stability: pos_drift={best['pos_drift']:.4f}m, rot_drift={best['rot_drift_deg']:.2f}°") |
|
|
| return results |
|
|
|
|
| def main(): |
| import argparse |
|
|
| parser = argparse.ArgumentParser(description="Physics-based pose refinement") |
| parser.add_argument("--output_dir", type=str, default="./outputs/mug_tree_goal", |
| help="Output directory with pipeline outputs") |
| parser.add_argument("--object_mesh_path", type=str, default="./assets/mug_0.glb", |
| help="Path to target object mesh") |
| parser.add_argument("--container_mesh_path", type=str, |
| default="./assets/metal_mug_holder/metal_mug_holder.obj", |
| help="Path to container mesh") |
| parser.add_argument("--table_path", type=str, |
| default="../video_gen_assets/table.glb", |
| help="Path to table mesh") |
| parser.add_argument("--num_samples", type=int, default=64, |
| help="Number of poses to sample") |
| parser.add_argument("--sequential", action="store_true", |
| help="Use sequential simulation instead of parallel") |
| parser.add_argument("--container_euler", type=float, nargs=3, default=[90.0, 0.0, 0.0], |
| help="Container euler angles in degrees (default: 90 0 0)") |
| parser.add_argument("--container_pos", type=float, nargs=3, default=None, |
| help="Override container position [x, y, z] (skip auto-z computation)") |
| parser.add_argument("--xy_jitter", type=float, default=0.02, |
| help="XY jitter range in meters (default: 0.02)") |
| parser.add_argument("--z_jitter", type=float, default=0.01, |
| help="Z jitter range in meters (default: 0.01)") |
| parser.add_argument("--xyz_jitter", type=float, nargs=3, default=None, |
| help="Per-axis jitter [x, y, z] in meters (overrides xy/z_jitter)") |
| parser.add_argument("--rot_jitter", type=float, nargs=3, default=[5.0, 5.0, 15.0], |
| help="Rotation jitter in degrees per axis (default: 5 5 15)") |
| parser.add_argument("--wall", action="store_true", |
| help="Use wall-mounted scene instead of table") |
| parser.add_argument("--wall_x", type=float, default=-0.5, |
| help="X position of wall plane (default: -0.5)") |
| parser.add_argument("--wall_height", type=float, default=1.2, |
| help="Z height to mount container on wall (default: 1.2)") |
| parser.add_argument("--container_scale", type=float, default=1.0, |
| help="Scale factor for container mesh (default: 1.0)") |
| parser.add_argument("--object_scale", type=float, default=1.0, |
| help="Scale factor for target object mesh (default: 1.0)") |
| parser.add_argument("--coacd_threshold", type=float, default=0.01, |
| help="CoACD threshold (default: 0.01)") |
| parser.add_argument("--coacd_resolution", type=int, default=80, |
| help="CoACD preprocess resolution (default: 80)") |
| parser.add_argument("--max_convex_hull", type=int, default=20, |
| help="CoACD max convex hulls (default: 20)") |
| parser.add_argument("--num_rounds", type=int, default=1, |
| help="Number of sampling rounds (default: 1)") |
| parser.add_argument("--max_pos_drift", type=float, default=0.03, |
| help="Max position drift for valid pose (meters, default: 0.03)") |
| parser.add_argument("--max_rot_drift", type=float, default=15.0, |
| help="Max rotation drift for valid pose (degrees, default: 15.0)") |
| parser.add_argument("--render_initial", action="store_true", |
| help="Render initial pose with collision meshes for debugging") |
|
|
| cli_args = parser.parse_args() |
|
|
| args = PhysicsRefineArgs( |
| output_dir=cli_args.output_dir, |
| object_mesh_path=cli_args.object_mesh_path, |
| container_mesh_path=cli_args.container_mesh_path, |
| table_path=cli_args.table_path, |
| num_samples=cli_args.num_samples, |
| use_parallel=not cli_args.sequential, |
| container_euler=tuple(cli_args.container_euler), |
| container_pos=tuple(cli_args.container_pos) if cli_args.container_pos else None, |
| xy_jitter=cli_args.xy_jitter, |
| z_jitter=cli_args.z_jitter, |
| rot_jitter_deg=tuple(cli_args.rot_jitter), |
| wall_mode=cli_args.wall, |
| wall_x=cli_args.wall_x, |
| wall_height=cli_args.wall_height, |
| coacd_threshold=cli_args.coacd_threshold, |
| coacd_resolution=cli_args.coacd_resolution, |
| max_convex_hull=cli_args.max_convex_hull, |
| num_rounds=cli_args.num_rounds, |
| render_initial=cli_args.render_initial, |
| object_scale=cli_args.object_scale, |
| max_pos_drift=cli_args.max_pos_drift, |
| max_rot_drift_deg=cli_args.max_rot_drift, |
| ) |
|
|
| refine_pose_physics(args) |
|
|
|
|
| if __name__ == "__main__": |
| main() |
|
|