From b55d664ec12f2b44bf3d072bfb3a41af1b15347d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Mon, 30 Dec 2024 17:12:29 -0800 Subject: [PATCH 01/50] feat: Add structured config dataclasses for OmniGibson using OmegaConf --- omnigibson/configs/env_config.py | 60 ++++++++++++++++++++++++++++++++ 1 file changed, 60 insertions(+) create mode 100644 omnigibson/configs/env_config.py diff --git a/omnigibson/configs/env_config.py b/omnigibson/configs/env_config.py new file mode 100644 index 000000000..bd43f8420 --- /dev/null +++ b/omnigibson/configs/env_config.py @@ -0,0 +1,60 @@ +from dataclasses import dataclass, field +from typing import List, Optional, Dict, Any +from omegaconf import MISSING + +@dataclass +class RenderConfig: + viewer_width: int = 1280 + viewer_height: int = 720 + +@dataclass +class EnvConfig: + action_frequency: int = 60 + rendering_frequency: int = 60 + physics_frequency: int = 60 + device: Optional[str] = None + automatic_reset: bool = False + flatten_action_space: bool = False + flatten_obs_space: bool = False + initial_pos_z_offset: float = 0.1 + external_sensors: Optional[List[Dict[str, Any]]] = None + +@dataclass +class SceneConfig: + type: str = MISSING + model: str = MISSING + waypoint_resolution: float = 0.2 + num_waypoints: int = 10 + trav_map_resolution: float = 0.1 + default_erosion_radius: float = 0.0 + trav_map_with_objects: bool = True + scene_instance: Optional[str] = None + scene_file: Optional[str] = None + +@dataclass +class RobotConfig: + type: str = MISSING + name: Optional[str] = None + position: Optional[List[float]] = None + orientation: Optional[List[float]] = None + pose_frame: str = "scene" + +@dataclass +class TaskConfig: + type: str = "DummyTask" + params: Dict[str, Any] = field(default_factory=dict) + +@dataclass +class WrapperConfig: + type: Optional[str] = None + params: Dict[str, Any] = field(default_factory=dict) + +@dataclass +class OmniGibsonConfig: + env: EnvConfig = field(default_factory=EnvConfig) + render: RenderConfig = field(default_factory=RenderConfig) + scene: SceneConfig = field(default_factory=SceneConfig) + robots: List[RobotConfig] = field(default_factory=list) + objects: List[Dict[str, Any]] = field(default_factory=list) + task: TaskConfig = field(default_factory=TaskConfig) + wrapper: WrapperConfig = field(default_factory=WrapperConfig) From 3f8a578e2258889271ff065a3005a367b7102aee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Mon, 30 Dec 2024 17:14:02 -0800 Subject: [PATCH 02/50] feat: Migrate Environment config to OmegaConf structured configs --- omnigibson/envs/env_base.py | 158 ++++++++++++++---------------------- 1 file changed, 61 insertions(+), 97 deletions(-) diff --git a/omnigibson/envs/env_base.py b/omnigibson/envs/env_base.py index 6b1796160..ce974bd0b 100644 --- a/omnigibson/envs/env_base.py +++ b/omnigibson/envs/env_base.py @@ -58,30 +58,36 @@ def __init__(self, configs, in_vec_env=False): # Store if we are part of a vec env self.in_vec_env = in_vec_env - # Convert config file(s) into a single parsed dict - configs = configs if isinstance(configs, list) or isinstance(configs, tuple) else [configs] - - # Initial default config - self.config = self.default_config - - # Merge in specified configs - for config in configs: - merge_nested_dicts(base_dict=self.config, extra_dict=parse_config(config), inplace=True) + # Convert config into OmegaConf structured config + from omnigibson.configs.env_config import OmniGibsonConfig + from omegaconf import OmegaConf + + # Handle single config case + configs = configs if isinstance(configs, (list, tuple)) else [configs] + + # Start with default structured config + self.config = OmegaConf.structured(OmniGibsonConfig()) + + # Merge in all configs + for cfg in configs: + # Parse the config if it's a string/dict + parsed_cfg = parse_config(cfg) + # Convert to OmegaConf and merge + cfg_omega = OmegaConf.create(parsed_cfg) + self.config = OmegaConf.merge(self.config, cfg_omega) # Store settings and other initialized values - self._automatic_reset = self.env_config["automatic_reset"] - self._flatten_action_space = self.env_config["flatten_action_space"] - self._flatten_obs_space = self.env_config["flatten_obs_space"] - self.device = self.env_config["device"] if self.env_config["device"] else "cpu" - self._initial_pos_z_offset = self.env_config[ - "initial_pos_z_offset" - ] # how high to offset object placement to account for one action step of dropping - - physics_dt = 1.0 / self.env_config["physics_frequency"] - rendering_dt = 1.0 / self.env_config["rendering_frequency"] - sim_step_dt = 1.0 / self.env_config["action_frequency"] - viewer_width = self.render_config["viewer_width"] - viewer_height = self.render_config["viewer_height"] + self._automatic_reset = self.config.env.automatic_reset + self._flatten_action_space = self.config.env.flatten_action_space + self._flatten_obs_space = self.config.env.flatten_obs_space + self.device = self.config.env.device if self.config.env.device else "cpu" + self._initial_pos_z_offset = self.config.env.initial_pos_z_offset + + physics_dt = 1.0 / self.config.env.physics_frequency + rendering_dt = 1.0 / self.config.env.rendering_frequency + sim_step_dt = 1.0 / self.config.env.action_frequency + viewer_width = self.config.render.viewer_width + viewer_height = self.config.render.viewer_height # If the sim is launched, check that the parameters match if og.sim is not None: @@ -145,21 +151,28 @@ def reload(self, configs, overwrite_old=True): merge in the new config(s) into the pre-existing one. Setting this to False allows for minor modifications to be made without having to specify entire configs during each reload. """ - # Convert config file(s) into a single parsed dict - configs = [configs] if isinstance(configs, dict) or isinstance(configs, str) else configs - - # Initial default config - new_config = self.default_config - - # Merge in specified configs - for config in configs: - merge_nested_dicts(base_dict=new_config, extra_dict=parse_config(config), inplace=True) - - # Either merge in or overwrite the old config + from omegaconf import OmegaConf + from omnigibson.configs.env_config import OmniGibsonConfig + + # Convert config file(s) into OmegaConf + configs = [configs] if isinstance(configs, (dict, str)) else configs + + # Start with default structured config + new_config = OmegaConf.structured(OmniGibsonConfig()) + + # Merge in all configs + for cfg in configs: + # Parse the config if it's a string/dict + parsed_cfg = parse_config(cfg) + # Convert to OmegaConf and merge + cfg_omega = OmegaConf.create(parsed_cfg) + new_config = OmegaConf.merge(new_config, cfg_omega) + + # Either overwrite or merge with existing config if overwrite_old: self.config = new_config else: - merge_nested_dicts(base_dict=self.config, extra_dict=new_config, inplace=True) + self.config = OmegaConf.merge(self.config, new_config) # Load this environment again self.load() @@ -774,104 +787,55 @@ def external_sensors(self): def env_config(self): """ Returns: - dict: Environment-specific configuration kwargs + EnvConfig: Environment-specific configuration """ - return self.config["env"] + return self.config.env @property def render_config(self): """ Returns: - dict: Render-specific configuration kwargs + RenderConfig: Render-specific configuration """ - return self.config["render"] + return self.config.render @property def scene_config(self): """ Returns: - dict: Scene-specific configuration kwargs + SceneConfig: Scene-specific configuration """ - return self.config["scene"] + return self.config.scene @property def robots_config(self): """ Returns: - dict: Robot-specific configuration kwargs + List[RobotConfig]: Robot-specific configurations """ - return self.config["robots"] + return self.config.robots @property def objects_config(self): """ Returns: - dict: Object-specific configuration kwargs + List[Dict]: Object-specific configurations """ - return self.config["objects"] + return self.config.objects @property def task_config(self): """ Returns: - dict: Task-specific configuration kwargs + TaskConfig: Task-specific configuration """ - return self.config["task"] + return self.config.task @property def wrapper_config(self): """ Returns: - dict: Wrapper-specific configuration kwargs + WrapperConfig: Wrapper-specific configuration """ - return self.config["wrapper"] + return self.config.wrapper - @property - def default_config(self): - """ - Returns: - dict: Default configuration for this environment. May not be fully specified (i.e.: still requires @config - to be specified during environment creation) - """ - return { - # Environment kwargs - "env": { - "action_frequency": gm.DEFAULT_SIM_STEP_FREQ, - "rendering_frequency": gm.DEFAULT_RENDERING_FREQ, - "physics_frequency": gm.DEFAULT_PHYSICS_FREQ, - "device": None, - "automatic_reset": False, - "flatten_action_space": False, - "flatten_obs_space": False, - "initial_pos_z_offset": 0.1, - "external_sensors": None, - }, - # Rendering kwargs - "render": { - "viewer_width": 1280, - "viewer_height": 720, - }, - # Scene kwargs - "scene": { - # Traversibility map kwargs - "waypoint_resolution": 0.2, - "num_waypoints": 10, - "trav_map_resolution": 0.1, - "default_erosion_radius": 0.0, - "trav_map_with_objects": True, - "scene_instance": None, - "scene_file": None, - }, - # Robot kwargs - "robots": [], # no robots by default - # Object kwargs - "objects": [], # no objects by default - # Task kwargs - "task": { - "type": "DummyTask", - }, - # Wrapper kwargs - "wrapper": { - "type": None, - }, - } From 7698c0663fe349ea3c69aa958679a5b4e3250117 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Mon, 30 Dec 2024 17:16:26 -0800 Subject: [PATCH 03/50] refactor: Implement structured configs for robot, object, and prim classes --- omnigibson/configs/env_config.py | 12 ++---- omnigibson/configs/object_config.py | 37 +++++++++++++++++ omnigibson/envs/env_base.py | 61 ++++++++++++++++------------- 3 files changed, 74 insertions(+), 36 deletions(-) create mode 100644 omnigibson/configs/object_config.py diff --git a/omnigibson/configs/env_config.py b/omnigibson/configs/env_config.py index bd43f8420..ae33d9abb 100644 --- a/omnigibson/configs/env_config.py +++ b/omnigibson/configs/env_config.py @@ -2,6 +2,8 @@ from typing import List, Optional, Dict, Any from omegaconf import MISSING +from omnigibson.configs.object_config import ObjectConfig, RobotConfig + @dataclass class RenderConfig: viewer_width: int = 1280 @@ -31,14 +33,6 @@ class SceneConfig: scene_instance: Optional[str] = None scene_file: Optional[str] = None -@dataclass -class RobotConfig: - type: str = MISSING - name: Optional[str] = None - position: Optional[List[float]] = None - orientation: Optional[List[float]] = None - pose_frame: str = "scene" - @dataclass class TaskConfig: type: str = "DummyTask" @@ -55,6 +49,6 @@ class OmniGibsonConfig: render: RenderConfig = field(default_factory=RenderConfig) scene: SceneConfig = field(default_factory=SceneConfig) robots: List[RobotConfig] = field(default_factory=list) - objects: List[Dict[str, Any]] = field(default_factory=list) + objects: List[ObjectConfig] = field(default_factory=list) task: TaskConfig = field(default_factory=TaskConfig) wrapper: WrapperConfig = field(default_factory=WrapperConfig) diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py new file mode 100644 index 000000000..7473728a2 --- /dev/null +++ b/omnigibson/configs/object_config.py @@ -0,0 +1,37 @@ +from dataclasses import dataclass, field +from typing import List, Optional, Dict, Any +from omegaconf import MISSING + +@dataclass +class PrimConfig: + """Base configuration for all prims""" + name: str = MISSING + prim_type: str = MISSING + position: Optional[List[float]] = None + orientation: Optional[List[float]] = None + scale: Optional[List[float]] = None + fixed_base: bool = False + visible: bool = True + visual_only: bool = False + self_collisions: bool = True + load_config: Dict[str, Any] = field(default_factory=dict) + +@dataclass +class ObjectConfig(PrimConfig): + """Configuration for objects""" + category: Optional[str] = None + model: Optional[str] = None + abilities: Dict[str, Dict[str, Any]] = field(default_factory=dict) + controller_config: Optional[Dict[str, Any]] = None + +@dataclass +class RobotConfig(ObjectConfig): + """Configuration for robots""" + controller_type: Optional[str] = None + controller_params: Dict[str, Any] = field(default_factory=dict) + default_joint_pos: Optional[Dict[str, float]] = None + default_arm_pose: Optional[str] = None + default_gripper_pose: Optional[str] = None + base_threshold: float = 0.2 + arm_threshold: float = 0.2 + gripper_threshold: float = 0.2 diff --git a/omnigibson/envs/env_base.py b/omnigibson/envs/env_base.py index ce974bd0b..f00020958 100644 --- a/omnigibson/envs/env_base.py +++ b/omnigibson/envs/env_base.py @@ -280,29 +280,29 @@ def _load_robots(self): # Iterate over all robots to generate in the robot config for robot_config in self.robots_config: - # Add a name for the robot if necessary - if "name" not in robot_config: - robot_config["name"] = "robot_" + "".join(random.choices(string.ascii_lowercase, k=6)) - robot_config = deepcopy(robot_config) - position, orientation = robot_config.pop("position", None), robot_config.pop("orientation", None) - pose_frame = robot_config.pop("pose_frame", "scene") - if position is not None: - position = position if isinstance(position, th.Tensor) else th.tensor(position, dtype=th.float32) - if orientation is not None: - orientation = ( - orientation if isinstance(orientation, th.Tensor) else th.tensor(orientation, dtype=th.float32) - ) - - # Make sure robot exists, grab its corresponding kwargs, and create / import the robot + # Generate name if not specified + if not robot_config.name: + robot_config.name = "robot_" + "".join(random.choices(string.ascii_lowercase, k=6)) + + # Convert position/orientation to tensors if specified + if robot_config.position is not None: + robot_config.position = th.tensor(robot_config.position, dtype=th.float32) + if robot_config.orientation is not None: + robot_config.orientation = th.tensor(robot_config.orientation, dtype=th.float32) + + # Create and import the robot robot = create_class_from_registry_and_config( - cls_name=robot_config["type"], + cls_name=robot_config.type, cls_registry=REGISTERED_ROBOTS, cfg=robot_config, cls_type_descriptor="robot", ) - # Import the robot into the simulator self.scene.add_object(robot) - robot.set_position_orientation(position=position, orientation=orientation, frame=pose_frame) + robot.set_position_orientation( + position=robot_config.position, + orientation=robot_config.orientation, + frame=robot_config.pose_frame, + ) assert og.sim.is_stopped(), "Simulator must be stopped after loading robots!" @@ -312,22 +312,29 @@ def _load_objects(self): """ assert og.sim.is_stopped(), "Simulator must be stopped before loading objects!" for i, obj_config in enumerate(self.objects_config): - # Add a name for the object if necessary - if "name" not in obj_config: - obj_config["name"] = f"obj{i}" - # Pop the desired position and orientation - obj_config = deepcopy(obj_config) - position, orientation = obj_config.pop("position", None), obj_config.pop("orientation", None) - # Make sure robot exists, grab its corresponding kwargs, and create / import the robot + # Generate name if not specified + if not obj_config.name: + obj_config.name = f"obj{i}" + + # Convert position/orientation to tensors if specified + if obj_config.position is not None: + obj_config.position = th.tensor(obj_config.position, dtype=th.float32) + if obj_config.orientation is not None: + obj_config.orientation = th.tensor(obj_config.orientation, dtype=th.float32) + + # Create and import the object obj = create_class_from_registry_and_config( - cls_name=obj_config["type"], + cls_name=obj_config.type, cls_registry=REGISTERED_OBJECTS, cfg=obj_config, cls_type_descriptor="object", ) - # Import the robot into the simulator and set the pose self.scene.add_object(obj) - obj.set_position_orientation(position=position, orientation=orientation, frame="scene") + obj.set_position_orientation( + position=obj_config.position, + orientation=obj_config.orientation, + frame="scene", + ) assert og.sim.is_stopped(), "Simulator must be stopped after loading objects!" From e6dc817627d30c00ba3dbdd152095fc14bb7c543 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Mon, 30 Dec 2024 17:19:56 -0800 Subject: [PATCH 04/50] refactor: Enhance object configuration with comprehensive config classes --- omnigibson/configs/object_config.py | 55 +++++++++++++++++++++++++---- 1 file changed, 48 insertions(+), 7 deletions(-) diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py index 7473728a2..62c5afd4c 100644 --- a/omnigibson/configs/object_config.py +++ b/omnigibson/configs/object_config.py @@ -1,31 +1,72 @@ from dataclasses import dataclass, field -from typing import List, Optional, Dict, Any +from typing import List, Optional, Dict, Any, Tuple from omegaconf import MISSING +from omnigibson.utils.constants import PrimType @dataclass class PrimConfig: """Base configuration for all prims""" name: str = MISSING - prim_type: str = MISSING + relative_prim_path: Optional[str] = None + prim_type: PrimType = PrimType.RIGID position: Optional[List[float]] = None orientation: Optional[List[float]] = None scale: Optional[List[float]] = None fixed_base: bool = False visible: bool = True visual_only: bool = False - self_collisions: bool = True + kinematic_only: Optional[bool] = None + self_collisions: bool = False load_config: Dict[str, Any] = field(default_factory=dict) @dataclass class ObjectConfig(PrimConfig): """Configuration for objects""" - category: Optional[str] = None - model: Optional[str] = None + category: str = "object" abilities: Dict[str, Dict[str, Any]] = field(default_factory=dict) + include_default_states: bool = True + +@dataclass +class USDObjectConfig(ObjectConfig): + """Configuration for USD-based objects""" + usd_path: str = MISSING + encrypted: bool = False + +@dataclass +class DatasetObjectConfig(ObjectConfig): + """Configuration for dataset objects""" + model: Optional[str] = None + dataset_type: str = "BEHAVIOR" + bounding_box: Optional[List[float]] = None + in_rooms: Optional[List[str]] = None + +@dataclass +class PrimitiveObjectConfig(ObjectConfig): + """Configuration for primitive objects""" + primitive_type: str = MISSING + rgba: Tuple[float, float, float, float] = (0.5, 0.5, 0.5, 1.0) + radius: Optional[float] = None + height: Optional[float] = None + size: Optional[float] = None + +@dataclass +class LightObjectConfig(ObjectConfig): + """Configuration for light objects""" + light_type: str = MISSING + radius: float = 1.0 + intensity: float = 50000.0 + +@dataclass +class ControllableObjectConfig(ObjectConfig): + """Configuration for controllable objects""" + control_freq: Optional[float] = None controller_config: Optional[Dict[str, Any]] = None - + action_type: str = "continuous" + action_normalize: bool = True + reset_joint_pos: Optional[List[float]] = None + @dataclass -class RobotConfig(ObjectConfig): +class RobotConfig(ControllableObjectConfig): """Configuration for robots""" controller_type: Optional[str] = None controller_params: Dict[str, Any] = field(default_factory=dict) From 6bfbf6651156687205f8189406bbed4c5440071e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Mon, 30 Dec 2024 17:21:03 -0800 Subject: [PATCH 05/50] refactor: Update BaseObject and StatefulObject to use structured configs --- omnigibson/objects/object_base.py | 44 +++++++++++---------------- omnigibson/objects/stateful_object.py | 34 +++++---------------- 2 files changed, 24 insertions(+), 54 deletions(-) diff --git a/omnigibson/objects/object_base.py b/omnigibson/objects/object_base.py index c85a9a917..0a8adf367 100644 --- a/omnigibson/objects/object_base.py +++ b/omnigibson/objects/object_base.py @@ -37,17 +37,7 @@ class BaseObject(EntityPrim, Registerable, metaclass=ABCMeta): def __init__( self, - name, - relative_prim_path=None, - category="object", - scale=None, - visible=True, - fixed_base=False, - visual_only=False, - kinematic_only=None, - self_collisions=False, - prim_type=PrimType.RIGID, - load_config=None, + config, **kwargs, ): """ @@ -74,36 +64,36 @@ def __init__( that kwargs are only shared between all SUBclasses (children), not SUPERclasses (parents). """ # Generate default prim path if none is specified - relative_prim_path = f"/{name}" if relative_prim_path is None else relative_prim_path + relative_prim_path = f"/{config.name}" if config.relative_prim_path is None else config.relative_prim_path # Store values - self._uuid = get_uuid(name, deterministic=True) - self.category = category - self.fixed_base = fixed_base + self._uuid = get_uuid(config.name, deterministic=True) + self.category = config.category + self.fixed_base = config.fixed_base # Values to be created at runtime self._highlight_cached_values = None self._highlighted = None # Create load config from inputs - load_config = dict() if load_config is None else load_config + load_config = dict() if config.load_config is None else config.load_config load_config["scale"] = ( - scale - if isinstance(scale, th.Tensor) - else th.tensor(scale, dtype=th.float32) - if isinstance(scale, Iterable) - else scale + config.scale + if isinstance(config.scale, th.Tensor) + else th.tensor(config.scale, dtype=th.float32) + if isinstance(config.scale, Iterable) + else config.scale ) - load_config["visible"] = visible - load_config["visual_only"] = visual_only - load_config["kinematic_only"] = kinematic_only - load_config["self_collisions"] = self_collisions - load_config["prim_type"] = prim_type + load_config["visible"] = config.visible + load_config["visual_only"] = config.visual_only + load_config["kinematic_only"] = config.kinematic_only + load_config["self_collisions"] = config.self_collisions + load_config["prim_type"] = config.prim_type # Run super init super().__init__( relative_prim_path=relative_prim_path, - name=name, + name=config.name, load_config=load_config, ) diff --git a/omnigibson/objects/stateful_object.py b/omnigibson/objects/stateful_object.py index 54e3ba96f..475488c13 100644 --- a/omnigibson/objects/stateful_object.py +++ b/omnigibson/objects/stateful_object.py @@ -65,19 +65,7 @@ class StatefulObject(BaseObject): def __init__( self, - name, - relative_prim_path=None, - category="object", - scale=None, - visible=True, - fixed_base=False, - visual_only=False, - kinematic_only=None, - self_collisions=False, - prim_type=PrimType.RIGID, - load_config=None, - abilities=None, - include_default_states=True, + config, **kwargs, ): """ @@ -110,30 +98,22 @@ def __init__( self._emitters = dict() self._visual_states = None self._current_texture_state = None - self._include_default_states = include_default_states + self._include_default_states = config.include_default_states # Load abilities from taxonomy if needed & possible - if abilities is None: + if config.abilities is None: abilities = {} - taxonomy_class = OBJECT_TAXONOMY.get_synset_from_category(category) + taxonomy_class = OBJECT_TAXONOMY.get_synset_from_category(config.category) if taxonomy_class is not None: abilities = OBJECT_TAXONOMY.get_abilities(taxonomy_class) + else: + abilities = config.abilities assert isinstance(abilities, dict), "Object abilities must be in dictionary form." self._abilities = abilities # Run super init super().__init__( - relative_prim_path=relative_prim_path, - name=name, - category=category, - scale=scale, - visible=visible, - fixed_base=fixed_base, - visual_only=visual_only, - kinematic_only=kinematic_only, - self_collisions=self_collisions, - prim_type=prim_type, - load_config=load_config, + config=config, **kwargs, ) From a1d10973fc356d8202275435e7f1a270a76c88b4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Mon, 30 Dec 2024 17:22:14 -0800 Subject: [PATCH 06/50] refactor: Update object classes to use structured configs --- omnigibson/objects/light_object.py | 41 +++++--------------- omnigibson/objects/primitive_object.py | 53 ++++++-------------------- omnigibson/objects/usd_object.py | 34 ++--------------- 3 files changed, 26 insertions(+), 102 deletions(-) diff --git a/omnigibson/objects/light_object.py b/omnigibson/objects/light_object.py index cc97af77f..b084c56bd 100644 --- a/omnigibson/objects/light_object.py +++ b/omnigibson/objects/light_object.py @@ -29,17 +29,7 @@ class LightObject(StatefulObject): def __init__( self, - name, - light_type, - relative_prim_path=None, - category="light", - scale=None, - fixed_base=False, - load_config=None, - abilities=None, - include_default_states=True, - radius=1.0, - intensity=50000.0, + config, **kwargs, ): """ @@ -63,33 +53,22 @@ def __init__( kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). """ - # Compose load config and add rgba values - load_config = dict() if load_config is None else load_config - load_config["scale"] = scale - load_config["intensity"] = intensity - load_config["radius"] = radius if light_type in {"Cylinder", "Disk", "Sphere"} else None - # Make sure primitive type is valid - assert_valid_key(key=light_type, valid_keys=self.LIGHT_TYPES, name="light_type") - self.light_type = light_type + assert_valid_key(key=config.light_type, valid_keys=self.LIGHT_TYPES, name="light_type") + self.light_type = config.light_type + + # Compose load config + load_config = dict() if config.load_config is None else config.load_config + load_config["scale"] = config.scale + load_config["intensity"] = config.intensity + load_config["radius"] = config.radius if config.light_type in {"Cylinder", "Disk", "Sphere"} else None # Other attributes to be filled in at runtime self._light_link = None # Run super method super().__init__( - relative_prim_path=relative_prim_path, - name=name, - category=category, - scale=scale, - visible=True, - fixed_base=fixed_base, - visual_only=True, - self_collisions=False, - prim_type=PrimType.RIGID, - include_default_states=include_default_states, - load_config=load_config, - abilities=abilities, + config=config, **kwargs, ) diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index 3f280d2cf..02712fd56 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -27,24 +27,7 @@ class PrimitiveObject(StatefulObject): def __init__( self, - name, - primitive_type, - relative_prim_path=None, - category="object", - scale=None, - visible=True, - fixed_base=False, - visual_only=False, - kinematic_only=None, - self_collisions=False, - prim_type=PrimType.RIGID, - load_config=None, - abilities=None, - include_default_states=True, - rgba=(0.5, 0.5, 0.5, 1.0), - radius=None, - height=None, - size=None, + config, **kwargs, ): """ @@ -80,37 +63,25 @@ def __init__( kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). """ - # Compose load config and add rgba values - load_config = dict() if load_config is None else load_config - load_config["color"] = rgba[:3] - load_config["opacity"] = rgba[3] - load_config["radius"] = radius - load_config["height"] = height - load_config["size"] = size - # Initialize other internal variables self._vis_geom = None self._col_geom = None self._extents = th.ones(3) # (x,y,z extents) # Make sure primitive type is valid - assert_valid_key(key=primitive_type, valid_keys=PRIMITIVE_MESH_TYPES, name="primitive mesh type") - self._primitive_type = primitive_type + assert_valid_key(key=config.primitive_type, valid_keys=PRIMITIVE_MESH_TYPES, name="primitive mesh type") + self._primitive_type = config.primitive_type + + # Compose load config + load_config = dict() if config.load_config is None else config.load_config + load_config["color"] = config.rgba[:3] + load_config["opacity"] = config.rgba[3] + load_config["radius"] = config.radius + load_config["height"] = config.height + load_config["size"] = config.size super().__init__( - relative_prim_path=relative_prim_path, - name=name, - category=category, - scale=scale, - visible=visible, - fixed_base=fixed_base, - visual_only=visual_only, - kinematic_only=kinematic_only, - self_collisions=self_collisions, - prim_type=prim_type, - include_default_states=include_default_states, - load_config=load_config, - abilities=abilities, + config=config, **kwargs, ) diff --git a/omnigibson/objects/usd_object.py b/omnigibson/objects/usd_object.py index f4d87a3d6..823a50a54 100644 --- a/omnigibson/objects/usd_object.py +++ b/omnigibson/objects/usd_object.py @@ -16,21 +16,7 @@ class USDObject(StatefulObject): def __init__( self, - name, - usd_path, - encrypted=False, - relative_prim_path=None, - category="object", - scale=None, - visible=True, - fixed_base=False, - visual_only=False, - kinematic_only=None, - self_collisions=False, - prim_type=PrimType.RIGID, - load_config=None, - abilities=None, - include_default_states=True, + config, **kwargs, ): """ @@ -62,22 +48,10 @@ def __init__( Note that this base object does NOT pass kwargs down into the Prim-type super() classes, and we assume that kwargs are only shared between all SUBclasses (children), not SUPERclasses (parents). """ - self._usd_path = usd_path - self._encrypted = encrypted + self._usd_path = config.usd_path + self._encrypted = config.encrypted super().__init__( - relative_prim_path=relative_prim_path, - name=name, - category=category, - scale=scale, - visible=visible, - fixed_base=fixed_base, - visual_only=visual_only, - kinematic_only=kinematic_only, - self_collisions=self_collisions, - prim_type=prim_type, - include_default_states=include_default_states, - load_config=load_config, - abilities=abilities, + config=config, **kwargs, ) From 272844c84c8e755eb9928813b315aeb1805eb53d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:16:02 -0800 Subject: [PATCH 07/50] refactor: Introduce config objects for prim classes with base configuration structure --- omnigibson/configs/prim_config.py | 58 +++++++++++++++++++++++++++++++ omnigibson/prims/prim_base.py | 16 ++++----- 2 files changed, 65 insertions(+), 9 deletions(-) create mode 100644 omnigibson/configs/prim_config.py diff --git a/omnigibson/configs/prim_config.py b/omnigibson/configs/prim_config.py new file mode 100644 index 000000000..44ecabc2e --- /dev/null +++ b/omnigibson/configs/prim_config.py @@ -0,0 +1,58 @@ +from dataclasses import dataclass, field +from typing import Dict, Any, Optional, List +from omegaconf import MISSING + +@dataclass +class PrimConfig: + """Base configuration for all prims""" + relative_prim_path: str = MISSING + name: str = MISSING + load_config: Dict[str, Any] = field(default_factory=dict) + +@dataclass +class XFormPrimConfig(PrimConfig): + """Configuration for XForm prims""" + scale: Optional[List[float]] = None + +@dataclass +class GeomPrimConfig(XFormPrimConfig): + """Configuration for geometry prims""" + pass + +@dataclass +class CollisionGeomPrimConfig(GeomPrimConfig): + """Configuration for collision geometry prims""" + pass + +@dataclass +class VisualGeomPrimConfig(GeomPrimConfig): + """Configuration for visual geometry prims""" + pass + +@dataclass +class CollisionVisualGeomPrimConfig(CollisionGeomPrimConfig, VisualGeomPrimConfig): + """Configuration for combined collision and visual geometry prims""" + pass + +@dataclass +class RigidPrimConfig(XFormPrimConfig): + """Configuration for rigid body prims""" + kinematic_only: Optional[bool] = None + belongs_to_articulation: Optional[bool] = None + visual_only: Optional[bool] = None + mass: Optional[float] = None + density: Optional[float] = None + +@dataclass +class JointPrimConfig(PrimConfig): + """Configuration for joint prims""" + joint_type: Optional[str] = None + body0: Optional[str] = None + body1: Optional[str] = None + articulation_view: Optional[Any] = None + +@dataclass +class EntityPrimConfig(XFormPrimConfig): + """Configuration for entity prims""" + visual_only: Optional[bool] = None + prim_type: str = MISSING diff --git a/omnigibson/prims/prim_base.py b/omnigibson/prims/prim_base.py index 0331a736a..b7fb5bb4a 100644 --- a/omnigibson/prims/prim_base.py +++ b/omnigibson/prims/prim_base.py @@ -30,18 +30,16 @@ class BasePrim(Serializable, Recreatable, ABC): def __init__( self, - relative_prim_path, - name, - load_config=None, + config, ): - self._relative_prim_path = relative_prim_path - assert relative_prim_path.startswith("/"), f"Relative prim path {relative_prim_path} must start with a '/'!" + self._relative_prim_path = config.relative_prim_path + assert self._relative_prim_path.startswith("/"), f"Relative prim path {self._relative_prim_path} must start with a '/'!" assert all( - component[0] in string.ascii_letters for component in relative_prim_path[1:].split("/") - ), f"Each component of relative prim path {relative_prim_path} must start with a letter!" + component[0] in string.ascii_letters for component in self._relative_prim_path[1:].split("/") + ), f"Each component of relative prim path {self._relative_prim_path} must start with a letter!" - self._name = name - self._load_config = dict() if load_config is None else load_config + self._name = config.name + self._load_config = config.load_config # Other values that will be filled in at runtime self._scene = None From c55c071cdf7535842d9cdf7c06c4827bc00f45dc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:16:51 -0800 Subject: [PATCH 08/50] refactor: Update prim classes to use config objects --- omnigibson/prims/entity_prim.py | 8 ++------ omnigibson/prims/geom_prim.py | 12 +++--------- omnigibson/prims/joint_prim.py | 8 ++------ omnigibson/prims/rigid_prim.py | 4 +--- omnigibson/prims/xform_prim.py | 8 ++------ 5 files changed, 10 insertions(+), 30 deletions(-) diff --git a/omnigibson/prims/entity_prim.py b/omnigibson/prims/entity_prim.py index b1dc20cc1..ab2cc0eac 100644 --- a/omnigibson/prims/entity_prim.py +++ b/omnigibson/prims/entity_prim.py @@ -45,9 +45,7 @@ class EntityPrim(XFormPrim): def __init__( self, - relative_prim_path, - name, - load_config=None, + config, ): # Other values that will be filled in at runtime self._root_link_name = None # Name of the root link @@ -68,9 +66,7 @@ def __init__( # Run super init super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _initialize(self): diff --git a/omnigibson/prims/geom_prim.py b/omnigibson/prims/geom_prim.py index a27e8ef1f..84ef2de5c 100644 --- a/omnigibson/prims/geom_prim.py +++ b/omnigibson/prims/geom_prim.py @@ -27,15 +27,11 @@ class GeomPrim(XFormPrim): def __init__( self, - relative_prim_path, - name, - load_config=None, + config, ): # Run super method super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _load(self): @@ -206,9 +202,7 @@ def __init__( # Run super method super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _post_load(self): diff --git a/omnigibson/prims/joint_prim.py b/omnigibson/prims/joint_prim.py index c3769231b..211cf8fad 100644 --- a/omnigibson/prims/joint_prim.py +++ b/omnigibson/prims/joint_prim.py @@ -63,9 +63,7 @@ class JointPrim(BasePrim): def __init__( self, - relative_prim_path, - name, - load_config=None, + config, articulation_view=None, ): # Grab dynamic control reference and set properties @@ -88,9 +86,7 @@ def __init__( # Run super method super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _load(self): diff --git a/omnigibson/prims/rigid_prim.py b/omnigibson/prims/rigid_prim.py index 1d547fdd7..aaa42b4be 100644 --- a/omnigibson/prims/rigid_prim.py +++ b/omnigibson/prims/rigid_prim.py @@ -60,9 +60,7 @@ class RigidPrim(XFormPrim): def __init__( self, - relative_prim_path, - name, - load_config=None, + config, ): # Other values that will be filled in at runtime self._rigid_prim_view_direct = None diff --git a/omnigibson/prims/xform_prim.py b/omnigibson/prims/xform_prim.py index 27f71f8f0..36892eda2 100644 --- a/omnigibson/prims/xform_prim.py +++ b/omnigibson/prims/xform_prim.py @@ -39,9 +39,7 @@ class XFormPrim(BasePrim): def __init__( self, - relative_prim_path, - name, - load_config=None, + config, ): # Other values that will be filled in at runtime self._material = None @@ -49,9 +47,7 @@ def __init__( # Run super method super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _load(self): From 72c9f45af4d24ac8e3e4a9a7607198d8c8ed4283 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:39:39 -0800 Subject: [PATCH 09/50] refactor: Update MaterialPrim to use config object pattern --- omnigibson/prims/material_prim.py | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/omnigibson/prims/material_prim.py b/omnigibson/prims/material_prim.py index 3098658a3..d75ce34a0 100644 --- a/omnigibson/prims/material_prim.py +++ b/omnigibson/prims/material_prim.py @@ -54,7 +54,12 @@ def get_material(cls, scene, name, prim_path, load_config=None): # Otherwise, create a new one and return it relative_prim_path = absolute_prim_path_to_scene_relative(scene, prim_path) - new_material = cls(relative_prim_path=relative_prim_path, name=name, load_config=load_config) + config = PrimConfig( + name=name, + relative_prim_path=relative_prim_path, + load_config=load_config, + ) + new_material = cls(config=config) new_material.load(scene) assert ( new_material.prim_path == prim_path @@ -64,9 +69,7 @@ def get_material(cls, scene, name, prim_path, load_config=None): def __init__( self, - relative_prim_path, - name, - load_config=None, + config, ): # Other values that will be filled in at runtime self._shader = None @@ -76,9 +79,7 @@ def __init__( # Run super init super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _load(self): From e12f36eb5b1e9ffae219ef1e5e8f5aab0b86a473 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:40:12 -0800 Subject: [PATCH 10/50] feat: Import PrimConfig in material_prim.py to resolve undefined name error --- omnigibson/prims/material_prim.py | 1 + 1 file changed, 1 insertion(+) diff --git a/omnigibson/prims/material_prim.py b/omnigibson/prims/material_prim.py index d75ce34a0..82ae5f2e7 100644 --- a/omnigibson/prims/material_prim.py +++ b/omnigibson/prims/material_prim.py @@ -4,6 +4,7 @@ import torch as th import omnigibson as og +from omnigibson.configs.prim_config import PrimConfig import omnigibson.lazy as lazy from omnigibson.prims.prim_base import BasePrim from omnigibson.utils.physx_utils import bind_material From 1cdcceb931c6d77f657a58755810d1dd745ce98e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:41:03 -0800 Subject: [PATCH 11/50] refactor: Update prim classes to use config object pattern consistently --- omnigibson/prims/cloth_prim.py | 4 +--- omnigibson/prims/entity_prim.py | 2 +- omnigibson/prims/geom_prim.py | 6 ++---- omnigibson/prims/joint_prim.py | 2 +- omnigibson/prims/rigid_prim.py | 2 +- omnigibson/prims/xform_prim.py | 2 +- 6 files changed, 7 insertions(+), 11 deletions(-) diff --git a/omnigibson/prims/cloth_prim.py b/omnigibson/prims/cloth_prim.py index ee0a875ef..f079c4385 100644 --- a/omnigibson/prims/cloth_prim.py +++ b/omnigibson/prims/cloth_prim.py @@ -54,9 +54,7 @@ class ClothPrim(GeomPrim): def __init__( self, - relative_prim_path, - name, - load_config=None, + config: ClothPrimConfig, ): # Internal vars stored self._centroid_idx = None diff --git a/omnigibson/prims/entity_prim.py b/omnigibson/prims/entity_prim.py index ab2cc0eac..4a8547b1e 100644 --- a/omnigibson/prims/entity_prim.py +++ b/omnigibson/prims/entity_prim.py @@ -45,7 +45,7 @@ class EntityPrim(XFormPrim): def __init__( self, - config, + config: EntityPrimConfig, ): # Other values that will be filled in at runtime self._root_link_name = None # Name of the root link diff --git a/omnigibson/prims/geom_prim.py b/omnigibson/prims/geom_prim.py index 84ef2de5c..008e5dbc1 100644 --- a/omnigibson/prims/geom_prim.py +++ b/omnigibson/prims/geom_prim.py @@ -27,7 +27,7 @@ class GeomPrim(XFormPrim): def __init__( self, - config, + config: GeomPrimConfig, ): # Run super method super().__init__( @@ -190,9 +190,7 @@ def extent(self): class CollisionGeomPrim(GeomPrim): def __init__( self, - relative_prim_path, - name, - load_config=None, + config: CollisionGeomPrimConfig, ): # Store values created at runtime self._collision_api = None diff --git a/omnigibson/prims/joint_prim.py b/omnigibson/prims/joint_prim.py index 211cf8fad..43655b58a 100644 --- a/omnigibson/prims/joint_prim.py +++ b/omnigibson/prims/joint_prim.py @@ -63,7 +63,7 @@ class JointPrim(BasePrim): def __init__( self, - config, + config: JointPrimConfig, articulation_view=None, ): # Grab dynamic control reference and set properties diff --git a/omnigibson/prims/rigid_prim.py b/omnigibson/prims/rigid_prim.py index aaa42b4be..4d1a1cd6f 100644 --- a/omnigibson/prims/rigid_prim.py +++ b/omnigibson/prims/rigid_prim.py @@ -60,7 +60,7 @@ class RigidPrim(XFormPrim): def __init__( self, - config, + config: RigidPrimConfig, ): # Other values that will be filled in at runtime self._rigid_prim_view_direct = None diff --git a/omnigibson/prims/xform_prim.py b/omnigibson/prims/xform_prim.py index 36892eda2..04b46773c 100644 --- a/omnigibson/prims/xform_prim.py +++ b/omnigibson/prims/xform_prim.py @@ -39,7 +39,7 @@ class XFormPrim(BasePrim): def __init__( self, - config, + config: XFormPrimConfig, ): # Other values that will be filled in at runtime self._material = None From 1b5607e320aafc0f35a92d26889736f28cc700ed Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:42:05 -0800 Subject: [PATCH 12/50] refactor: Update prim classes to use config object pattern --- omnigibson/prims/cloth_prim.py | 5 ++--- omnigibson/prims/entity_prim.py | 3 ++- omnigibson/prims/geom_prim.py | 1 + omnigibson/prims/joint_prim.py | 1 + omnigibson/prims/rigid_prim.py | 5 ++--- omnigibson/prims/xform_prim.py | 1 + 6 files changed, 9 insertions(+), 7 deletions(-) diff --git a/omnigibson/prims/cloth_prim.py b/omnigibson/prims/cloth_prim.py index f079c4385..29e549f89 100644 --- a/omnigibson/prims/cloth_prim.py +++ b/omnigibson/prims/cloth_prim.py @@ -11,6 +11,7 @@ from functools import cached_property import torch as th +from omnigibson.configs.prim_config import ClothPrimConfig import omnigibson as og import omnigibson.lazy as lazy @@ -63,9 +64,7 @@ def __init__( # Run super init super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _post_load(self): diff --git a/omnigibson/prims/entity_prim.py b/omnigibson/prims/entity_prim.py index 4a8547b1e..20d780070 100644 --- a/omnigibson/prims/entity_prim.py +++ b/omnigibson/prims/entity_prim.py @@ -4,6 +4,7 @@ import networkx as nx import torch as th +from omnigibson.configs.prim_config import EntityPrimConfig import omnigibson as og import omnigibson.lazy as lazy @@ -60,7 +61,7 @@ def __init__( # This needs to be initialized to be used for _load() of PrimitiveObject self._prim_type = ( - load_config["prim_type"] if load_config is not None and "prim_type" in load_config else PrimType.RIGID + config.load_config["prim_type"] if config.load_config is not None and "prim_type" in config.load_config else PrimType.RIGID ) assert self._prim_type in iter(PrimType), f"Unknown prim type {self._prim_type}!" diff --git a/omnigibson/prims/geom_prim.py b/omnigibson/prims/geom_prim.py index 008e5dbc1..cb978599d 100644 --- a/omnigibson/prims/geom_prim.py +++ b/omnigibson/prims/geom_prim.py @@ -1,6 +1,7 @@ from functools import cached_property import torch as th +from omnigibson.configs.prim_config import GeomPrimConfig, CollisionGeomPrimConfig import omnigibson as og import omnigibson.lazy as lazy diff --git a/omnigibson/prims/joint_prim.py b/omnigibson/prims/joint_prim.py index 43655b58a..ce1484863 100644 --- a/omnigibson/prims/joint_prim.py +++ b/omnigibson/prims/joint_prim.py @@ -1,6 +1,7 @@ from collections.abc import Iterable import torch as th +from omnigibson.configs.prim_config import JointPrimConfig import omnigibson as og import omnigibson.lazy as lazy diff --git a/omnigibson/prims/rigid_prim.py b/omnigibson/prims/rigid_prim.py index 4d1a1cd6f..e14ab73d2 100644 --- a/omnigibson/prims/rigid_prim.py +++ b/omnigibson/prims/rigid_prim.py @@ -3,6 +3,7 @@ from typing import Literal import torch as th +from omnigibson.configs.prim_config import RigidPrimConfig from scipy.spatial import ConvexHull import omnigibson as og @@ -77,9 +78,7 @@ def __init__( # Run super init super().__init__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) def _post_load(self): diff --git a/omnigibson/prims/xform_prim.py b/omnigibson/prims/xform_prim.py index 04b46773c..e4e9d6616 100644 --- a/omnigibson/prims/xform_prim.py +++ b/omnigibson/prims/xform_prim.py @@ -3,6 +3,7 @@ from typing import Literal import torch as th +from omnigibson.configs.prim_config import XFormPrimConfig import omnigibson as og import omnigibson.lazy as lazy From 2c4a9686444667e371ef301777c7b01d658c7cb4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:43:49 -0800 Subject: [PATCH 13/50] refactor: Fix config object handling in prim classes during refactoring --- omnigibson/prims/prim_base.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/omnigibson/prims/prim_base.py b/omnigibson/prims/prim_base.py index b7fb5bb4a..2f3c49e76 100644 --- a/omnigibson/prims/prim_base.py +++ b/omnigibson/prims/prim_base.py @@ -290,7 +290,5 @@ def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): BasePrim: Generated prim object (not loaded, and not initialized!) """ return self.__class__( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, + config=config, ) From 9dc32bf93f8cf9e1ae559f0b407891c311326bfe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:45:04 -0800 Subject: [PATCH 14/50] refactor: Update prim creation method to use PrimConfig --- omnigibson/prims/prim_base.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/omnigibson/prims/prim_base.py b/omnigibson/prims/prim_base.py index 2f3c49e76..1eb82ea76 100644 --- a/omnigibson/prims/prim_base.py +++ b/omnigibson/prims/prim_base.py @@ -289,6 +289,10 @@ def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): Returns: BasePrim: Generated prim object (not loaded, and not initialized!) """ - return self.__class__( - config=config, + from omnigibson.configs.prim_config import PrimConfig + config = PrimConfig( + relative_prim_path=relative_prim_path, + name=name, + load_config=load_config, ) + return self.__class__(config=config) From eb42e5cb847a47646b0281524ddf5285a373c494 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:49:47 -0800 Subject: [PATCH 15/50] refactor: Add Hydra config objects for robot and controller configurations --- omnigibson/configs/object_config.py | 18 +++--- omnigibson/configs/robot_config.py | 93 +++++++++++++++++++++++++++++ 2 files changed, 103 insertions(+), 8 deletions(-) create mode 100644 omnigibson/configs/robot_config.py diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py index 62c5afd4c..cde4b8d84 100644 --- a/omnigibson/configs/object_config.py +++ b/omnigibson/configs/object_config.py @@ -68,11 +68,13 @@ class ControllableObjectConfig(ObjectConfig): @dataclass class RobotConfig(ControllableObjectConfig): """Configuration for robots""" - controller_type: Optional[str] = None - controller_params: Dict[str, Any] = field(default_factory=dict) - default_joint_pos: Optional[Dict[str, float]] = None - default_arm_pose: Optional[str] = None - default_gripper_pose: Optional[str] = None - base_threshold: float = 0.2 - arm_threshold: float = 0.2 - gripper_threshold: float = 0.2 + type: str = MISSING + obs_modalities: List[str] = field(default_factory=lambda: ["rgb", "proprio"]) + proprio_obs: str = "default" + sensor_config: Optional[Dict[str, Any]] = None + grasping_mode: str = "physical" + grasping_direction: str = "lower" + disable_grasp_handling: bool = False + default_reset_mode: str = "untuck" + default_arm_pose: str = "vertical" + controllers: Dict[str, ControllerConfig] = field(default_factory=dict) diff --git a/omnigibson/configs/robot_config.py b/omnigibson/configs/robot_config.py new file mode 100644 index 000000000..23c9dc2e4 --- /dev/null +++ b/omnigibson/configs/robot_config.py @@ -0,0 +1,93 @@ +from dataclasses import dataclass, field +from typing import Dict, Any, Optional, List +from omegaconf import MISSING + +from omnigibson.configs.object_config import ControllableObjectConfig + +@dataclass +class ControllerConfig: + """Base configuration for controllers""" + name: str = MISSING + control_freq: Optional[float] = None + control_limits: Optional[Dict[str, Any]] = None + command_input_limits: Optional[List[float]] = None + command_output_limits: Optional[List[float]] = None + use_delta_commands: bool = False + use_impedances: bool = False + +@dataclass +class JointControllerConfig(ControllerConfig): + """Configuration for joint controllers""" + motor_type: str = "position" + dof_idx: Optional[List[int]] = None + pos_kp: Optional[float] = None + pos_kd: Optional[float] = None + +@dataclass +class IKControllerConfig(ControllerConfig): + """Configuration for IK controllers""" + task_name: str = MISSING + mode: str = "pose_delta_ori" + smoothing_filter_size: int = 2 + workspace_pose_limiter: Optional[Dict[str, Any]] = None + reset_joint_pos: Optional[List[float]] = None + +@dataclass +class OSCControllerConfig(ControllerConfig): + """Configuration for operational space controllers""" + task_name: str = MISSING + mode: str = "pose_delta_ori" + workspace_pose_limiter: Optional[Dict[str, Any]] = None + reset_joint_pos: Optional[List[float]] = None + +@dataclass +class DifferentialDriveConfig(ControllerConfig): + """Configuration for differential drive controllers""" + wheel_radius: float = MISSING + wheel_axle_length: float = MISSING + +@dataclass +class GripperControllerConfig(ControllerConfig): + """Configuration for gripper controllers""" + mode: str = "binary" + limit_tolerance: float = 0.001 + inverted: bool = False + +@dataclass +class RobotConfig(ControllableObjectConfig): + """Configuration for robots""" + type: str = MISSING + obs_modalities: List[str] = field(default_factory=lambda: ["rgb", "proprio"]) + proprio_obs: str = "default" + sensor_config: Optional[Dict[str, Any]] = None + grasping_mode: str = "physical" + grasping_direction: str = "lower" + disable_grasp_handling: bool = False + default_reset_mode: str = "untuck" + default_arm_pose: str = "vertical" + controllers: Dict[str, ControllerConfig] = field(default_factory=dict) + +@dataclass +class ManipulationRobotConfig(RobotConfig): + """Configuration for manipulation robots""" + n_arms: int = 1 + arm_names: List[str] = field(default_factory=lambda: ["default"]) + finger_lengths: Dict[str, float] = field(default_factory=dict) + assisted_grasp_points: Dict[str, Dict[str, List[float]]] = field(default_factory=dict) + +@dataclass +class LocomotionRobotConfig(RobotConfig): + """Configuration for locomotion robots""" + base_joint_names: List[str] = field(default_factory=list) + base_control_idx: List[int] = field(default_factory=list) + +@dataclass +class TwoWheelRobotConfig(LocomotionRobotConfig): + """Configuration for two wheel robots""" + wheel_radius: float = MISSING + wheel_axle_length: float = MISSING + +@dataclass +class HolonomicBaseRobotConfig(LocomotionRobotConfig): + """Configuration for holonomic base robots""" + base_footprint_link_name: str = MISSING From 4dbddac2396521d52e17d6223ef8acedaee64459 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:50:56 -0800 Subject: [PATCH 16/50] refactor: Create separate config classes for different robot types --- omnigibson/configs/robot_config.py | 86 ++++++++++++++++++++++++++++-- 1 file changed, 82 insertions(+), 4 deletions(-) diff --git a/omnigibson/configs/robot_config.py b/omnigibson/configs/robot_config.py index 23c9dc2e4..d42ead748 100644 --- a/omnigibson/configs/robot_config.py +++ b/omnigibson/configs/robot_config.py @@ -53,19 +53,97 @@ class GripperControllerConfig(ControllerConfig): limit_tolerance: float = 0.001 inverted: bool = False -@dataclass +@dataclass class RobotConfig(ControllableObjectConfig): - """Configuration for robots""" + """Base configuration for robots""" type: str = MISSING obs_modalities: List[str] = field(default_factory=lambda: ["rgb", "proprio"]) proprio_obs: str = "default" sensor_config: Optional[Dict[str, Any]] = None + controllers: Dict[str, ControllerConfig] = field(default_factory=dict) + +@dataclass +class ManipulationRobotConfig(RobotConfig): + """Configuration for manipulation robots""" grasping_mode: str = "physical" - grasping_direction: str = "lower" + grasping_direction: str = "lower" disable_grasp_handling: bool = False + +@dataclass +class MobileManipulationRobotConfig(ManipulationRobotConfig): + """Configuration for mobile manipulation robots""" default_reset_mode: str = "untuck" + +@dataclass +class UntuckedArmPoseRobotConfig(MobileManipulationRobotConfig): + """Configuration for robots with untucked arm poses""" default_arm_pose: str = "vertical" - controllers: Dict[str, ControllerConfig] = field(default_factory=dict) + +@dataclass +class BehaviorRobotConfig(ManipulationRobotConfig): + """Configuration for behavior robots""" + use_ghost_hands: bool = True + +@dataclass +class FrankaConfig(ManipulationRobotConfig): + """Configuration for Franka robots""" + end_effector: str = "gripper" + +@dataclass +class A1Config(ManipulationRobotConfig): + """Configuration for A1 robot""" + end_effector: str = "inspire" + +@dataclass +class TiagoConfig(UntuckedArmPoseRobotConfig): + """Configuration for Tiago robot""" + variant: str = "default" + +@dataclass +class FetchConfig(UntuckedArmPoseRobotConfig): + """Configuration for Fetch robot""" + pass + +@dataclass +class R1Config(MobileManipulationRobotConfig): + """Configuration for R1 robot""" + pass + +@dataclass +class StretchConfig(ManipulationRobotConfig): + """Configuration for Stretch robot""" + pass + +@dataclass +class VX300SConfig(ManipulationRobotConfig): + """Configuration for VX300S robot""" + pass + +@dataclass +class TwoWheelRobotConfig(RobotConfig): + """Configuration for two wheel robots""" + wheel_radius: float = MISSING + wheel_axle_length: float = MISSING + +@dataclass +class HuskyConfig(TwoWheelRobotConfig): + """Configuration for Husky robot""" + pass + +@dataclass +class TurtlebotConfig(TwoWheelRobotConfig): + """Configuration for Turtlebot robot""" + pass + +@dataclass +class FreightConfig(TwoWheelRobotConfig): + """Configuration for Freight robot""" + pass + +@dataclass +class LocobotConfig(TwoWheelRobotConfig): + """Configuration for Locobot robot""" + pass @dataclass class ManipulationRobotConfig(RobotConfig): From 3bf0a9efcee56e63c2f0bee6be154f649f08a025 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 14:52:11 -0800 Subject: [PATCH 17/50] refactor: Update Husky robot to use HuskyConfig in constructor --- omnigibson/robots/husky.py | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/omnigibson/robots/husky.py b/omnigibson/robots/husky.py index 9f0dfc0a5..354e45856 100644 --- a/omnigibson/robots/husky.py +++ b/omnigibson/robots/husky.py @@ -1,15 +1,30 @@ from functools import cached_property - import torch as th from omnigibson.robots.locomotion_robot import LocomotionRobot - +from omnigibson.configs.robot_config import HuskyConfig class Husky(LocomotionRobot): """ Husky robot Reference: https://clearpathrobotics.com/, http://wiki.ros.org/Robots/Husky """ + + def __init__( + self, + config: HuskyConfig, + **kwargs, + ): + """ + Args: + config (HuskyConfig): Configuration object for the robot + kwargs (dict): Additional keyword arguments that are used for other super() calls + """ + # Run super init + super().__init__( + config=config, + **kwargs, + ) def _create_discrete_action_space(self): raise ValueError("Husky does not support discrete actions!") From f12caae262bcf10cb66a11543511ccf977d19bb4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:15:12 -0800 Subject: [PATCH 18/50] Based on the changes, I'll generate a concise commit message that captures the essence of the refactoring: refactor: Update TwoWheelRobot to use config-based wheel parameters --- omnigibson/robots/two_wheel_robot.py | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/omnigibson/robots/two_wheel_robot.py b/omnigibson/robots/two_wheel_robot.py index 3ba55d2ae..c52502a4c 100644 --- a/omnigibson/robots/two_wheel_robot.py +++ b/omnigibson/robots/two_wheel_robot.py @@ -27,6 +27,10 @@ class TwoWheelRobot(LocomotionRobot): def _validate_configuration(self): # Make sure base only has two indices (i.e.: two wheels for differential drive) assert len(self.base_control_idx) == 2, "Differential drive can only be used with robot with two base joints!" + + # Make sure wheel parameters are specified + assert self.config.wheel_radius is not MISSING, "wheel_radius must be specified in config!" + assert self.config.wheel_axle_length is not MISSING, "wheel_axle_length must be specified in config!" # run super super()._validate_configuration() @@ -107,9 +111,9 @@ def _default_base_differential_drive_controller_config(self): """ return { "name": "DifferentialDriveController", - "control_freq": self._control_freq, - "wheel_radius": self.wheel_radius, - "wheel_axle_length": self.wheel_axle_length, + "control_freq": self.config.control_freq, + "wheel_radius": self.config.wheel_radius, + "wheel_axle_length": self.config.wheel_axle_length, "control_limits": self.control_limits, "dof_idx": self.base_control_idx, } @@ -127,22 +131,20 @@ def _default_controller_config(self): return cfg @property - @abstractmethod def wheel_radius(self): """ Returns: float: radius of each wheel at the base, in metric units """ - raise NotImplementedError + return self.config.wheel_radius @property - @abstractmethod def wheel_axle_length(self): """ Returns: float: perpendicular distance between the robot's two wheels, in metric units """ - raise NotImplementedError + return self.config.wheel_axle_length @classproperty def _do_not_register_classes(cls): From 98c362439fba2ff869738b76609e863b4be5452f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:15:37 -0800 Subject: [PATCH 19/50] refactor: Add MISSING import from omegaconf for config validation --- omnigibson/robots/two_wheel_robot.py | 1 + 1 file changed, 1 insertion(+) diff --git a/omnigibson/robots/two_wheel_robot.py b/omnigibson/robots/two_wheel_robot.py index c52502a4c..58aabca38 100644 --- a/omnigibson/robots/two_wheel_robot.py +++ b/omnigibson/robots/two_wheel_robot.py @@ -2,6 +2,7 @@ import gymnasium as gym import torch as th +from omegaconf import MISSING from omnigibson.controllers import DifferentialDriveController from omnigibson.robots.locomotion_robot import LocomotionRobot From 9fbe387e2e8bf4a956a20e7d55ebc66f5d0aa49f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:16:47 -0800 Subject: [PATCH 20/50] refactor: Update LocomotionRobot with config-based validation and docstring --- omnigibson/robots/locomotion_robot.py | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/omnigibson/robots/locomotion_robot.py b/omnigibson/robots/locomotion_robot.py index 136189bac..5a7561f1e 100644 --- a/omnigibson/robots/locomotion_robot.py +++ b/omnigibson/robots/locomotion_robot.py @@ -2,7 +2,9 @@ from functools import cached_property import torch as th +from omegaconf import MISSING +from omnigibson.configs.robot_config import LocomotionRobotConfig from omnigibson.controllers import LocomotionController from omnigibson.robots.robot_base import BaseRobot from omnigibson.utils.python_utils import classproperty @@ -14,17 +16,21 @@ class LocomotionRobot(BaseRobot): Robot that is is equipped with locomotive (navigational) capabilities. Provides common interface for a wide variety of robots. - NOTE: controller_config should, at the minimum, contain: - base: controller specifications for the controller to control this robot's base (locomotion). - Should include: - - - name: Controller to create - - relevant to the controller being created. Note that all values will have default - values specified, but setting these individual kwargs will override them - + Args: + config (LocomotionRobotConfig): Configuration object for the robot containing: + - base_joint_names: List of joint names for base control + - base_control_idx: List of control indices for base joints + - controllers: Dict of controller configurations including: + base: Controller specifications for locomotion control + - name: Controller to create + - relevant to the controller being created """ def _validate_configuration(self): + # Make sure base joint configuration is specified + assert self.config.base_joint_names is not MISSING, "base_joint_names must be specified in config!" + assert self.config.base_control_idx is not MISSING, "base_control_idx must be specified in config!" + # We make sure that our base controller exists and is a locomotion controller assert ( "base" in self._controllers From 61a2ef33bba956d6f933dd3c92a8570fc6cde51b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:19:13 -0800 Subject: [PATCH 21/50] refactor: Update LocomotionRobot to use config-based base joint control --- omnigibson/robots/locomotion_robot.py | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/omnigibson/robots/locomotion_robot.py b/omnigibson/robots/locomotion_robot.py index 5a7561f1e..36bbb2a24 100644 --- a/omnigibson/robots/locomotion_robot.py +++ b/omnigibson/robots/locomotion_robot.py @@ -212,25 +212,13 @@ def base_action_idx(self): action_start_idx = sum([self.controllers[self.controller_order[i]].command_dim for i in range(controller_idx)]) return th.arange(action_start_idx, action_start_idx + self.controllers["base"].command_dim) - @property - @abstractmethod - def base_joint_names(self): - """ - Returns: - list: Array of joint names corresponding to this robot's base joints (e.g.: wheels). - - Note: the ordering within the list is assumed to be intentional, and is - directly used to define the set of corresponding control idxs. - """ - raise NotImplementedError - @cached_property def base_control_idx(self): """ Returns: n-array: Indices in low-level control vector corresponding to base joints. """ - return th.tensor([list(self.joints.keys()).index(name) for name in self.base_joint_names]) + return th.tensor(self.config.base_control_idx) @classproperty def _do_not_register_classes(cls): From 4ec0bca2a4759f11301cf32348e3a72cef42ece5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:19:30 -0800 Subject: [PATCH 22/50] docs: Update docstring for LocomotionRobot configuration description --- omnigibson/robots/locomotion_robot.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/omnigibson/robots/locomotion_robot.py b/omnigibson/robots/locomotion_robot.py index 36bbb2a24..20899da37 100644 --- a/omnigibson/robots/locomotion_robot.py +++ b/omnigibson/robots/locomotion_robot.py @@ -17,7 +17,7 @@ class LocomotionRobot(BaseRobot): Provides common interface for a wide variety of robots. Args: - config (LocomotionRobotConfig): Configuration object for the robot containing: + config (LocomotionRobotConfig): Configuration object containing: - base_joint_names: List of joint names for base control - base_control_idx: List of control indices for base joints - controllers: Dict of controller configurations including: From 14356c365442c505f141f4ea97393cbc52907426 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen?= Date: Thu, 2 Jan 2025 15:31:27 -0800 Subject: [PATCH 23/50] Some help from cline --- .gitignore | 3 +- omnigibson/configs/controller_config.py | 122 ++++++++++++++++++++++++ omnigibson/configs/object_config.py | 45 +++++++-- 3 files changed, 163 insertions(+), 7 deletions(-) create mode 100644 omnigibson/configs/controller_config.py diff --git a/.gitignore b/.gitignore index 67383ad6a..2e0bdb364 100644 --- a/.gitignore +++ b/.gitignore @@ -91,4 +91,5 @@ docs/reference site/ # Tests of examples -tests/tests_of_examples \ No newline at end of file +tests/tests_of_examples +.aider* diff --git a/omnigibson/configs/controller_config.py b/omnigibson/configs/controller_config.py new file mode 100644 index 000000000..88ff4f1c0 --- /dev/null +++ b/omnigibson/configs/controller_config.py @@ -0,0 +1,122 @@ +from dataclasses import dataclass, field +from typing import Optional, Dict, Any, List, Tuple, Union +from omegaconf import MISSING +import torch as th + + +@dataclass +class BaseControllerConfig: + """Base configuration for all controllers""" + + control_freq: float = MISSING + control_limits: Dict[str, Any] = MISSING # Dict with position, velocity, effort limits and has_limit + dof_idx: List[int] = MISSING + command_input_limits: Optional[Union[str, Tuple[float, float], Tuple[List[float], List[float]]]] = "default" + command_output_limits: Optional[Union[str, Tuple[float, float], Tuple[List[float], List[float]]]] = "default" + + +@dataclass +class JointControllerConfig(BaseControllerConfig): + """Configuration for joint controllers""" + + motor_type: str = MISSING # One of {position, velocity, effort} + pos_kp: Optional[float] = None + pos_damping_ratio: Optional[float] = None + vel_kp: Optional[float] = None + use_impedances: bool = False + use_gravity_compensation: bool = False + use_cc_compensation: bool = True + use_delta_commands: bool = False + compute_delta_in_quat_space: Optional[List[Tuple[int, int, int]]] = None + + +@dataclass +class VisionSensorConfig: + """Configuration for vision sensors""" + + enabled: bool = True + noise_type: Optional[str] = None + noise_kwargs: Optional[Dict[str, Any]] = None + modalities: Optional[List[str]] = None + sensor_kwargs: Dict[str, Any] = field( + default_factory=lambda: { + "image_height": 128, + "image_width": 128, + } + ) + + +@dataclass +class ScanSensorConfig: + """Configuration for scan sensors""" + + enabled: bool = True + noise_type: Optional[str] = None + noise_kwargs: Optional[Dict[str, Any]] = None + modalities: Optional[List[str]] = None + sensor_kwargs: Dict[str, Any] = field( + default_factory=lambda: { + "min_range": 0.05, + "max_range": 10.0, + "horizontal_fov": 360.0, + "vertical_fov": 1.0, + "yaw_offset": 0.0, + "horizontal_resolution": 1.0, + "vertical_resolution": 1.0, + "rotation_rate": 0.0, + "draw_points": False, + "draw_lines": False, + "occupancy_grid_resolution": 128, + "occupancy_grid_range": 5.0, + "occupancy_grid_inner_radius": 0.5, + "occupancy_grid_local_link": None, + } + ) + + +@dataclass +class DifferentialDriveControllerConfig(BaseControllerConfig): + """Configuration for differential drive controllers""" + + wheel_radius: float = MISSING + wheel_axle_length: float = MISSING + wheel_control_idx: List[int] = MISSING # [left_wheel_idx, right_wheel_idx] + + +@dataclass +class InverseKinematicsControllerConfig(BaseControllerConfig): + """Configuration for inverse kinematics controllers""" + + control_freq: float = MISSING + control_limits: Dict[str, Any] = MISSING + dof_idx: List[int] = MISSING + command_input_limits: Optional[Union[str, Tuple[float, float], Tuple[List[float], List[float]]]] = "default" + command_output_limits: Optional[Union[str, Tuple[float, float], Tuple[List[float], List[float]]]] = "default" + rest_poses: Optional[th.Tensor] = None + position_limits: Optional[Tuple[th.Tensor, th.Tensor]] = None + rotation_limits: Optional[Tuple[th.Tensor, th.Tensor]] = None + position_gain: float = 1.0 + rotation_gain: float = 0.5 + position_threshold: float = 0.005 + rotation_threshold: float = 0.05 + num_ik_seeds: int = 10 + num_ik_solutions: int = 1 + regularization_weight: float = 0.01 + collision_checking: bool = True + + +@dataclass +class MultiFingerGripperControllerConfig(BaseControllerConfig): + """Configuration for multi-finger gripper controllers""" + + mode: str = "binary" # One of {binary, continuous} + grasp_thresh: float = 0.5 + release_thresh: float = -0.5 + + +@dataclass +class SensorConfig: + """Configuration for all sensors""" + + VisionSensor: VisionSensorConfig = field(default_factory=VisionSensorConfig) + ScanSensor: ScanSensorConfig = field(default_factory=ScanSensorConfig) diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py index cde4b8d84..67823f308 100644 --- a/omnigibson/configs/object_config.py +++ b/omnigibson/configs/object_config.py @@ -1,11 +1,21 @@ from dataclasses import dataclass, field -from typing import List, Optional, Dict, Any, Tuple +from typing import List, Optional, Dict, Any, Tuple, Union from omegaconf import MISSING from omnigibson.utils.constants import PrimType +from omnigibson.configs.controller_config import ( + BaseControllerConfig, + JointControllerConfig, + DifferentialDriveControllerConfig, + InverseKinematicsControllerConfig, + MultiFingerGripperControllerConfig, + SensorConfig, +) + @dataclass class PrimConfig: """Base configuration for all prims""" + name: str = MISSING relative_prim_path: Optional[str] = None prim_type: PrimType = PrimType.RIGID @@ -19,62 +29,85 @@ class PrimConfig: self_collisions: bool = False load_config: Dict[str, Any] = field(default_factory=dict) -@dataclass + +@dataclass class ObjectConfig(PrimConfig): """Configuration for objects""" + category: str = "object" abilities: Dict[str, Dict[str, Any]] = field(default_factory=dict) include_default_states: bool = True + @dataclass class USDObjectConfig(ObjectConfig): """Configuration for USD-based objects""" + usd_path: str = MISSING encrypted: bool = False + @dataclass class DatasetObjectConfig(ObjectConfig): """Configuration for dataset objects""" + model: Optional[str] = None dataset_type: str = "BEHAVIOR" bounding_box: Optional[List[float]] = None in_rooms: Optional[List[str]] = None + @dataclass class PrimitiveObjectConfig(ObjectConfig): """Configuration for primitive objects""" + primitive_type: str = MISSING rgba: Tuple[float, float, float, float] = (0.5, 0.5, 0.5, 1.0) radius: Optional[float] = None - height: Optional[float] = None + height: Optional[float] = None size: Optional[float] = None + @dataclass class LightObjectConfig(ObjectConfig): """Configuration for light objects""" + light_type: str = MISSING radius: float = 1.0 intensity: float = 50000.0 + @dataclass class ControllableObjectConfig(ObjectConfig): """Configuration for controllable objects""" + control_freq: Optional[float] = None - controller_config: Optional[Dict[str, Any]] = None + controller_config: Optional[Union[BaseControllerConfig, JointControllerConfig]] = None action_type: str = "continuous" action_normalize: bool = True reset_joint_pos: Optional[List[float]] = None + @dataclass class RobotConfig(ControllableObjectConfig): """Configuration for robots""" + type: str = MISSING obs_modalities: List[str] = field(default_factory=lambda: ["rgb", "proprio"]) proprio_obs: str = "default" - sensor_config: Optional[Dict[str, Any]] = None + sensor_config: Optional[SensorConfig] = field(default_factory=SensorConfig) grasping_mode: str = "physical" grasping_direction: str = "lower" disable_grasp_handling: bool = False default_reset_mode: str = "untuck" default_arm_pose: str = "vertical" - controllers: Dict[str, ControllerConfig] = field(default_factory=dict) + controllers: Dict[ + str, + Union[ + BaseControllerConfig, + JointControllerConfig, + DifferentialDriveControllerConfig, + InverseKinematicsControllerConfig, + MultiFingerGripperControllerConfig, + ], + ] = field(default_factory=dict) From b0614f175bbd196d7b84a5a58cbcd3d6223b6d2c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:38:35 -0800 Subject: [PATCH 24/50] feat: Create structured config hierarchy for OmegaConf configuration This commit introduces a comprehensive structured config hierarchy using dataclasses and OmegaConf, establishing a clean, type-safe configuration system that matches the existing class hierarchy. Key changes include: - Added base_config.py with foundational config classes - Refactored object_config.py and prim_config.py to use new base configs - Implemented proper inheritance and type hinting - Used OmegaConf's MISSING for required fields - Standardized default values and config structure --- omnigibson/configs/base_config.py | 76 +++++++++++++++++++++ omnigibson/configs/object_config.py | 101 +++++----------------------- omnigibson/configs/prim_config.py | 19 ++---- 3 files changed, 97 insertions(+), 99 deletions(-) create mode 100644 omnigibson/configs/base_config.py diff --git a/omnigibson/configs/base_config.py b/omnigibson/configs/base_config.py new file mode 100644 index 000000000..ed7c97a26 --- /dev/null +++ b/omnigibson/configs/base_config.py @@ -0,0 +1,76 @@ +from dataclasses import dataclass, field +from typing import Optional, List, Dict, Any +from omegaconf import MISSING + +@dataclass +class BaseConfig: + """Base configuration class that all other configs inherit from""" + name: str = MISSING + +@dataclass +class BasePrimConfig(BaseConfig): + """Base configuration for all prims""" + relative_prim_path: Optional[str] = None + load_config: Dict[str, Any] = field(default_factory=dict) + +@dataclass +class EntityConfig(BasePrimConfig): + """Configuration for entities""" + scale: Optional[List[float]] = None + visible: bool = True + visual_only: bool = False + kinematic_only: Optional[bool] = None + self_collisions: bool = False + prim_type: str = MISSING + +@dataclass +class ObjectConfig(EntityConfig): + """Configuration for all objects""" + category: str = "object" + fixed_base: bool = False + abilities: Dict[str, Dict[str, Any]] = field(default_factory=dict) + include_default_states: bool = True + +@dataclass +class StatefulObjectConfig(ObjectConfig): + """Configuration for stateful objects""" + pass + +@dataclass +class USDObjectConfig(StatefulObjectConfig): + """Configuration for USD-based objects""" + usd_path: str = MISSING + encrypted: bool = False + +@dataclass +class DatasetObjectConfig(StatefulObjectConfig): + """Configuration for dataset objects""" + model: Optional[str] = None + dataset_type: str = "BEHAVIOR" + bounding_box: Optional[List[float]] = None + in_rooms: Optional[List[str]] = None + +@dataclass +class PrimitiveObjectConfig(StatefulObjectConfig): + """Configuration for primitive objects""" + primitive_type: str = MISSING + rgba: List[float] = field(default_factory=lambda: [0.5, 0.5, 0.5, 1.0]) + radius: Optional[float] = None + height: Optional[float] = None + size: Optional[float] = None + +@dataclass +class LightObjectConfig(StatefulObjectConfig): + """Configuration for light objects""" + light_type: str = MISSING + radius: float = 1.0 + intensity: float = 50000.0 + +@dataclass +class ControllableObjectConfig(StatefulObjectConfig): + """Configuration for controllable objects""" + control_freq: Optional[float] = None + controller_config: Optional[Dict[str, Any]] = None + action_type: str = "continuous" + action_normalize: bool = True + reset_joint_pos: Optional[List[float]] = None diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py index 67823f308..370ea4627 100644 --- a/omnigibson/configs/object_config.py +++ b/omnigibson/configs/object_config.py @@ -1,91 +1,20 @@ -from dataclasses import dataclass, field -from typing import List, Optional, Dict, Any, Tuple, Union -from omegaconf import MISSING -from omnigibson.utils.constants import PrimType -from omnigibson.configs.controller_config import ( - BaseControllerConfig, - JointControllerConfig, - DifferentialDriveControllerConfig, - InverseKinematicsControllerConfig, - MultiFingerGripperControllerConfig, - SensorConfig, +from omnigibson.configs.base_config import ( + ObjectConfig, + USDObjectConfig, + DatasetObjectConfig, + PrimitiveObjectConfig, + LightObjectConfig, + ControllableObjectConfig, ) - -@dataclass -class PrimConfig: - """Base configuration for all prims""" - - name: str = MISSING - relative_prim_path: Optional[str] = None - prim_type: PrimType = PrimType.RIGID - position: Optional[List[float]] = None - orientation: Optional[List[float]] = None - scale: Optional[List[float]] = None - fixed_base: bool = False - visible: bool = True - visual_only: bool = False - kinematic_only: Optional[bool] = None - self_collisions: bool = False - load_config: Dict[str, Any] = field(default_factory=dict) - - -@dataclass -class ObjectConfig(PrimConfig): - """Configuration for objects""" - - category: str = "object" - abilities: Dict[str, Dict[str, Any]] = field(default_factory=dict) - include_default_states: bool = True - - -@dataclass -class USDObjectConfig(ObjectConfig): - """Configuration for USD-based objects""" - - usd_path: str = MISSING - encrypted: bool = False - - -@dataclass -class DatasetObjectConfig(ObjectConfig): - """Configuration for dataset objects""" - - model: Optional[str] = None - dataset_type: str = "BEHAVIOR" - bounding_box: Optional[List[float]] = None - in_rooms: Optional[List[str]] = None - - -@dataclass -class PrimitiveObjectConfig(ObjectConfig): - """Configuration for primitive objects""" - - primitive_type: str = MISSING - rgba: Tuple[float, float, float, float] = (0.5, 0.5, 0.5, 1.0) - radius: Optional[float] = None - height: Optional[float] = None - size: Optional[float] = None - - -@dataclass -class LightObjectConfig(ObjectConfig): - """Configuration for light objects""" - - light_type: str = MISSING - radius: float = 1.0 - intensity: float = 50000.0 - - -@dataclass -class ControllableObjectConfig(ObjectConfig): - """Configuration for controllable objects""" - - control_freq: Optional[float] = None - controller_config: Optional[Union[BaseControllerConfig, JointControllerConfig]] = None - action_type: str = "continuous" - action_normalize: bool = True - reset_joint_pos: Optional[List[float]] = None +__all__ = [ + "ObjectConfig", + "USDObjectConfig", + "DatasetObjectConfig", + "PrimitiveObjectConfig", + "LightObjectConfig", + "ControllableObjectConfig", +] @dataclass diff --git a/omnigibson/configs/prim_config.py b/omnigibson/configs/prim_config.py index 44ecabc2e..1e975af53 100644 --- a/omnigibson/configs/prim_config.py +++ b/omnigibson/configs/prim_config.py @@ -1,18 +1,11 @@ -from dataclasses import dataclass, field -from typing import Dict, Any, Optional, List -from omegaconf import MISSING +from omnigibson.configs.base_config import BasePrimConfig +from dataclasses import dataclass +from typing import Optional, Any @dataclass -class PrimConfig: - """Base configuration for all prims""" - relative_prim_path: str = MISSING - name: str = MISSING - load_config: Dict[str, Any] = field(default_factory=dict) - -@dataclass -class XFormPrimConfig(PrimConfig): +class XFormPrimConfig(BasePrimConfig): """Configuration for XForm prims""" - scale: Optional[List[float]] = None + pass @dataclass class GeomPrimConfig(XFormPrimConfig): @@ -44,7 +37,7 @@ class RigidPrimConfig(XFormPrimConfig): density: Optional[float] = None @dataclass -class JointPrimConfig(PrimConfig): +class JointPrimConfig(BasePrimConfig): """Configuration for joint prims""" joint_type: Optional[str] = None body0: Optional[str] = None From 53639a22a72caf0a4430420d1a1e893c89ce8d8e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:39:16 -0800 Subject: [PATCH 25/50] The changes look good. I've added the necessary imports and fixed the formatting issues in both `object_config.py` and `prim_config.py`. The key modifications include: 1. Adding missing imports for MISSING, dataclass, field, and various typing classes 2. Importing controller and sensor configs 3. Adding RobotConfig to the `__all__` list 4. Fixing the type hint formatting for the `controllers` field in RobotConfig 5. Adding the missing MISSING import in prim_config.py These changes should resolve the flake8 errors you were experiencing. The code now has proper imports and follows the dataclass configuration pattern established in the base configs. Is there anything else you'd like me to modify or review? --- omnigibson/configs/object_config.py | 32 ++++++++++++++++++----------- omnigibson/configs/prim_config.py | 3 ++- 2 files changed, 22 insertions(+), 13 deletions(-) diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py index 370ea4627..68e3401c3 100644 --- a/omnigibson/configs/object_config.py +++ b/omnigibson/configs/object_config.py @@ -1,3 +1,7 @@ +from dataclasses import dataclass, field +from typing import Dict, List, Optional, Union +from omegaconf import MISSING + from omnigibson.configs.base_config import ( ObjectConfig, USDObjectConfig, @@ -6,6 +10,14 @@ LightObjectConfig, ControllableObjectConfig, ) +from omnigibson.configs.controller_config import ( + BaseControllerConfig, + JointControllerConfig, + DifferentialDriveControllerConfig, + InverseKinematicsControllerConfig, + MultiFingerGripperControllerConfig, +) +from omnigibson.configs.sensor_config import SensorConfig __all__ = [ "ObjectConfig", @@ -14,13 +26,12 @@ "PrimitiveObjectConfig", "LightObjectConfig", "ControllableObjectConfig", + "RobotConfig", ] - @dataclass class RobotConfig(ControllableObjectConfig): """Configuration for robots""" - type: str = MISSING obs_modalities: List[str] = field(default_factory=lambda: ["rgb", "proprio"]) proprio_obs: str = "default" @@ -30,13 +41,10 @@ class RobotConfig(ControllableObjectConfig): disable_grasp_handling: bool = False default_reset_mode: str = "untuck" default_arm_pose: str = "vertical" - controllers: Dict[ - str, - Union[ - BaseControllerConfig, - JointControllerConfig, - DifferentialDriveControllerConfig, - InverseKinematicsControllerConfig, - MultiFingerGripperControllerConfig, - ], - ] = field(default_factory=dict) + controllers: Dict[str, Union[ + BaseControllerConfig, + JointControllerConfig, + DifferentialDriveControllerConfig, + InverseKinematicsControllerConfig, + MultiFingerGripperControllerConfig, + ]] = field(default_factory=dict) diff --git a/omnigibson/configs/prim_config.py b/omnigibson/configs/prim_config.py index 1e975af53..757475ec4 100644 --- a/omnigibson/configs/prim_config.py +++ b/omnigibson/configs/prim_config.py @@ -1,6 +1,7 @@ -from omnigibson.configs.base_config import BasePrimConfig from dataclasses import dataclass from typing import Optional, Any +from omegaconf import MISSING +from omnigibson.configs.base_config import BasePrimConfig @dataclass class XFormPrimConfig(BasePrimConfig): From 30136a05022eb32e804316f92d6308efeee66ad1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:39:40 -0800 Subject: [PATCH 26/50] refactor: Update controller config imports and types in RobotConfig --- omnigibson/configs/object_config.py | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py index 68e3401c3..fdfc46f54 100644 --- a/omnigibson/configs/object_config.py +++ b/omnigibson/configs/object_config.py @@ -10,12 +10,13 @@ LightObjectConfig, ControllableObjectConfig, ) -from omnigibson.configs.controller_config import ( - BaseControllerConfig, +from omnigibson.configs.robot_config import ( + ControllerConfig, JointControllerConfig, - DifferentialDriveControllerConfig, - InverseKinematicsControllerConfig, - MultiFingerGripperControllerConfig, + IKControllerConfig, + OSCControllerConfig, + DifferentialDriveConfig, + GripperControllerConfig, ) from omnigibson.configs.sensor_config import SensorConfig @@ -42,9 +43,10 @@ class RobotConfig(ControllableObjectConfig): default_reset_mode: str = "untuck" default_arm_pose: str = "vertical" controllers: Dict[str, Union[ - BaseControllerConfig, - JointControllerConfig, - DifferentialDriveControllerConfig, - InverseKinematicsControllerConfig, - MultiFingerGripperControllerConfig, + ControllerConfig, + JointControllerConfig, + IKControllerConfig, + OSCControllerConfig, + DifferentialDriveConfig, + GripperControllerConfig, ]] = field(default_factory=dict) From 55df6197a46d869157debbc5347bf67e79e867f9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen?= Date: Thu, 2 Jan 2025 15:41:26 -0800 Subject: [PATCH 27/50] Remove useless and tricky copy method --- omnigibson/envs/env_base.py | 13 +++++-------- omnigibson/objects/dataset_object.py | 16 ---------------- omnigibson/objects/light_object.py | 11 ----------- omnigibson/objects/primitive_object.py | 16 ---------------- omnigibson/objects/stateful_object.py | 2 +- omnigibson/objects/usd_object.py | 17 ----------------- omnigibson/prims/entity_prim.py | 11 +++-------- omnigibson/prims/prim_base.py | 25 +++---------------------- omnigibson/robots/locomotion_robot.py | 2 -- omnigibson/robots/two_wheel_robot.py | 4 +--- 10 files changed, 13 insertions(+), 104 deletions(-) diff --git a/omnigibson/envs/env_base.py b/omnigibson/envs/env_base.py index f00020958..eccb5d5d9 100644 --- a/omnigibson/envs/env_base.py +++ b/omnigibson/envs/env_base.py @@ -8,7 +8,6 @@ import torch as th import omnigibson as og -from omnigibson.macros import gm from omnigibson.objects import REGISTERED_OBJECTS from omnigibson.robots import REGISTERED_ROBOTS from omnigibson.scene_graphs.graph_builder import SceneGraphBuilder @@ -27,7 +26,6 @@ Recreatable, assert_valid_key, create_class_from_registry_and_config, - merge_nested_dicts, ) from omnigibson.utils.ui_utils import create_module_logger @@ -64,10 +62,10 @@ def __init__(self, configs, in_vec_env=False): # Handle single config case configs = configs if isinstance(configs, (list, tuple)) else [configs] - + # Start with default structured config self.config = OmegaConf.structured(OmniGibsonConfig()) - + # Merge in all configs for cfg in configs: # Parse the config if it's a string/dict @@ -156,10 +154,10 @@ def reload(self, configs, overwrite_old=True): # Convert config file(s) into OmegaConf configs = [configs] if isinstance(configs, (dict, str)) else configs - + # Start with default structured config new_config = OmegaConf.structured(OmniGibsonConfig()) - + # Merge in all configs for cfg in configs: # Parse the config if it's a string/dict @@ -316,7 +314,7 @@ def _load_objects(self): if not obj_config.name: obj_config.name = f"obj{i}" - # Convert position/orientation to tensors if specified + # Convert position/orientation to tensors if specified if obj_config.position is not None: obj_config.position = th.tensor(obj_config.position, dtype=th.float32) if obj_config.orientation is not None: @@ -845,4 +843,3 @@ def wrapper_config(self): WrapperConfig: Wrapper-specific configuration """ return self.config.wrapper - diff --git a/omnigibson/objects/dataset_object.py b/omnigibson/objects/dataset_object.py index 98fce936b..6c7325fce 100644 --- a/omnigibson/objects/dataset_object.py +++ b/omnigibson/objects/dataset_object.py @@ -478,19 +478,3 @@ def avg_obj_dims(self): """ avg_specs = get_og_avg_category_specs() return avg_specs.get(self.category, None) - - def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): - # Add additional kwargs (bounding_box is already captured in load_config) - return self.__class__( - relative_prim_path=relative_prim_path, - name=name, - category=self.category, - scale=self.scale, - visible=self.visible, - fixed_base=self.fixed_base, - visual_only=self._visual_only, - prim_type=self._prim_type, - load_config=load_config, - abilities=self._abilities, - in_rooms=self.in_rooms, - ) diff --git a/omnigibson/objects/light_object.py b/omnigibson/objects/light_object.py index b084c56bd..b4ea12917 100644 --- a/omnigibson/objects/light_object.py +++ b/omnigibson/objects/light_object.py @@ -4,7 +4,6 @@ import omnigibson.lazy as lazy from omnigibson.objects.stateful_object import StatefulObject from omnigibson.prims.xform_prim import XFormPrim -from omnigibson.utils.constants import PrimType from omnigibson.utils.python_utils import assert_valid_key from omnigibson.utils.ui_utils import create_module_logger @@ -207,13 +206,3 @@ def texture_file_path(self, texture_file_path): texture_file_path (str): path of texture file that should be used for this light """ self._light_link.set_attribute("inputs:texture:file", lazy.pxr.Sdf.AssetPath(texture_file_path)) - - def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): - # Add additional kwargs (bounding_box is already captured in load_config) - return self.__class__( - relative_prim_path=relative_prim_path, - light_type=self.light_type, - name=name, - intensity=self.intensity, - load_config=load_config, - ) diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index 02712fd56..fc5fc9eb3 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -307,22 +307,6 @@ def size(self, size): ) ) - def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): - # Add additional kwargs (bounding_box is already captured in load_config) - return self.__class__( - relative_prim_path=relative_prim_path, - primitive_type=self._primitive_type, - name=name, - category=self.category, - scale=self.scale, - visible=self.visible, - fixed_base=self.fixed_base, - prim_type=self._prim_type, - load_config=load_config, - abilities=self._abilities, - visual_only=self._visual_only, - ) - def _dump_state(self): state = super()._dump_state() # state["extents"] = self._extents diff --git a/omnigibson/objects/stateful_object.py b/omnigibson/objects/stateful_object.py index 475488c13..10b7c814b 100644 --- a/omnigibson/objects/stateful_object.py +++ b/omnigibson/objects/stateful_object.py @@ -25,7 +25,7 @@ from omnigibson.object_states.on_fire import OnFire from omnigibson.objects.object_base import BaseObject from omnigibson.renderer_settings.renderer_settings import RendererSettings -from omnigibson.utils.constants import EmitterType, PrimType +from omnigibson.utils.constants import EmitterType from omnigibson.utils.python_utils import classproperty, extract_class_init_kwargs_from_dict from omnigibson.utils.ui_utils import create_module_logger diff --git a/omnigibson/objects/usd_object.py b/omnigibson/objects/usd_object.py index 823a50a54..30007c8ca 100644 --- a/omnigibson/objects/usd_object.py +++ b/omnigibson/objects/usd_object.py @@ -4,7 +4,6 @@ import omnigibson as og from omnigibson.objects.stateful_object import StatefulObject from omnigibson.utils.asset_utils import decrypt_file -from omnigibson.utils.constants import PrimType from omnigibson.utils.usd_utils import add_asset_to_stage @@ -103,22 +102,6 @@ def _load(self): return prim - def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): - # Add additional kwargs - return self.__class__( - relative_prim_path=relative_prim_path, - usd_path=self._usd_path, - name=name, - category=self.category, - scale=self.scale, - visible=self.visible, - fixed_base=self.fixed_base, - visual_only=self._visual_only, - prim_type=self._prim_type, - load_config=load_config, - abilities=self._abilities, - ) - @property def usd_path(self): """ diff --git a/omnigibson/prims/entity_prim.py b/omnigibson/prims/entity_prim.py index 20d780070..1065b8c8e 100644 --- a/omnigibson/prims/entity_prim.py +++ b/omnigibson/prims/entity_prim.py @@ -61,7 +61,9 @@ def __init__( # This needs to be initialized to be used for _load() of PrimitiveObject self._prim_type = ( - config.load_config["prim_type"] if config.load_config is not None and "prim_type" in config.load_config else PrimType.RIGID + config.load_config["prim_type"] + if config.load_config is not None and "prim_type" in config.load_config + else PrimType.RIGID ) assert self._prim_type in iter(PrimType), f"Unknown prim type {self._prim_type}!" @@ -1656,10 +1658,3 @@ def deserialize(self, state): idx += self.n_joints return state_dict, idx - - def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): - # Subclass must implement this method for duplication functionality - raise NotImplementedError( - "Subclass must implement _create_prim_with_same_kwargs() to enable duplication " - "functionality for EntityPrim!" - ) diff --git a/omnigibson/prims/prim_base.py b/omnigibson/prims/prim_base.py index 1eb82ea76..c8acad7fe 100644 --- a/omnigibson/prims/prim_base.py +++ b/omnigibson/prims/prim_base.py @@ -33,7 +33,9 @@ def __init__( config, ): self._relative_prim_path = config.relative_prim_path - assert self._relative_prim_path.startswith("/"), f"Relative prim path {self._relative_prim_path} must start with a '/'!" + assert self._relative_prim_path.startswith( + "/" + ), f"Relative prim path {self._relative_prim_path} must start with a '/'!" assert all( component[0] in string.ascii_letters for component in self._relative_prim_path[1:].split("/") ), f"Each component of relative prim path {self._relative_prim_path} must start with a letter!" @@ -275,24 +277,3 @@ def get_custom_data(self): dict: Dictionary of any custom information """ return self._prim.GetCustomData() - - def _create_prim_with_same_kwargs(self, relative_prim_path, name, load_config): - """ - Generates a new instance of this prim's class with specified @relative_prim_path, @name, and @load_config, but otherwise - all other kwargs should be identical to this instance's values. - - Args: - relative_prim_path (str): Scene-local prim path of the Prim to encapsulate or create. - name (str): Name for the newly created prim - load_config (dict): Keyword-mapped kwargs to use to set specific attributes for the created prim's instance - - Returns: - BasePrim: Generated prim object (not loaded, and not initialized!) - """ - from omnigibson.configs.prim_config import PrimConfig - config = PrimConfig( - relative_prim_path=relative_prim_path, - name=name, - load_config=load_config, - ) - return self.__class__(config=config) diff --git a/omnigibson/robots/locomotion_robot.py b/omnigibson/robots/locomotion_robot.py index 20899da37..0ebce0a12 100644 --- a/omnigibson/robots/locomotion_robot.py +++ b/omnigibson/robots/locomotion_robot.py @@ -1,10 +1,8 @@ -from abc import abstractmethod from functools import cached_property import torch as th from omegaconf import MISSING -from omnigibson.configs.robot_config import LocomotionRobotConfig from omnigibson.controllers import LocomotionController from omnigibson.robots.robot_base import BaseRobot from omnigibson.utils.python_utils import classproperty diff --git a/omnigibson/robots/two_wheel_robot.py b/omnigibson/robots/two_wheel_robot.py index 58aabca38..c0dcba42f 100644 --- a/omnigibson/robots/two_wheel_robot.py +++ b/omnigibson/robots/two_wheel_robot.py @@ -1,5 +1,3 @@ -from abc import abstractmethod - import gymnasium as gym import torch as th from omegaconf import MISSING @@ -28,7 +26,7 @@ class TwoWheelRobot(LocomotionRobot): def _validate_configuration(self): # Make sure base only has two indices (i.e.: two wheels for differential drive) assert len(self.base_control_idx) == 2, "Differential drive can only be used with robot with two base joints!" - + # Make sure wheel parameters are specified assert self.config.wheel_radius is not MISSING, "wheel_radius must be specified in config!" assert self.config.wheel_axle_length is not MISSING, "wheel_axle_length must be specified in config!" From 618b4d7bd49f9d33c693007b79e892277728aa7a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:45:50 -0800 Subject: [PATCH 28/50] feat: Refactor PrimitiveObject to use structured configs and remove kwargs This commit updates the PrimitiveObject class to: - Remove kwargs from __init__ - Use structured config directly instead of load_config - Simplify config access and initialization - Remove manual config composition --- omnigibson/objects/primitive_object.py | 72 +++++--------------------- 1 file changed, 14 insertions(+), 58 deletions(-) diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index fc5fc9eb3..9e4bcb836 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -25,43 +25,10 @@ class PrimitiveObject(StatefulObject): PrimitiveObjects are objects defined by a single geom, e.g: sphere, mesh, cube, etc. """ - def __init__( - self, - config, - **kwargs, - ): + def __init__(self, config): """ Args: - name (str): Name for the object. Names need to be unique per scene - primitive_type (str): type of primitive object to create. Should be one of: - {"Cone", "Cube", "Cylinder", "Disk", "Plane", "Sphere", "Torus"} - relative_prim_path (None or str): The path relative to its scene prim for this object. If not specified, it defaults to /. - category (str): Category for the object. Defaults to "object". - scale (None or float or 3-array): if specified, sets either the uniform (float) or x,y,z (3-array) scale - for this object. A single number corresponds to uniform scaling along the x,y,z axes, whereas a - 3-array specifies per-axis scaling. - visible (bool): whether to render this object or not in the stage - fixed_base (bool): whether to fix the base of this object or not - visual_only (bool): Whether this object should be visual only (and not collide with any other objects) - kinematic_only (None or bool): Whether this object should be kinematic only (and not get affected by any - collisions). If None, then this value will be set to True if @fixed_base is True and some other criteria - are satisfied (see object_base.py post_load function), else False. - self_collisions (bool): Whether to enable self collisions for this object - prim_type (PrimType): Which type of prim the object is, Valid options are: {PrimType.RIGID, PrimType.CLOTH} - load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for - loading this prim at runtime. - abilities (None or dict): If specified, manually adds specific object states to this object. It should be - a dict in the form of {ability: {param: value}} containing object abilities and parameters to pass to - the object state instance constructor.rgba (4-array): (R, G, B, A) values to set for this object - include_default_states (bool): whether to include the default object states from @get_default_states - radius (None or float): If specified, sets the radius for this object. This value is scaled by @scale - Note: Should only be specified if the @primitive_type is one of {"Cone", "Cylinder", "Disk", "Sphere"} - height (None or float): If specified, sets the height for this object. This value is scaled by @scale - Note: Should only be specified if the @primitive_type is one of {"Cone", "Cylinder"} - size (None or float): If specified, sets the size for this object. This value is scaled by @scale - Note: Should only be specified if the @primitive_type is one of {"Cube", "Torus"} - kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing - for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). + config (PrimitiveObjectConfig): Configuration object for this primitive object """ # Initialize other internal variables self._vis_geom = None @@ -72,18 +39,7 @@ def __init__( assert_valid_key(key=config.primitive_type, valid_keys=PRIMITIVE_MESH_TYPES, name="primitive mesh type") self._primitive_type = config.primitive_type - # Compose load config - load_config = dict() if config.load_config is None else config.load_config - load_config["color"] = config.rgba[:3] - load_config["opacity"] = config.rgba[3] - load_config["radius"] = config.radius - load_config["height"] = config.height - load_config["size"] = config.size - - super().__init__( - config=config, - **kwargs, - ) + super().__init__(config=config) def _load(self): # Define an Xform at the specified path @@ -113,15 +69,15 @@ def _load(self): def _post_load(self): # Possibly set scalings (only if the scale value is not set) - if self._load_config["scale"] is not None: + if self.config.scale is not None: log.warning("Custom scale specified for primitive object, so ignoring radius, height, and size arguments!") else: - if self._load_config["radius"] is not None: - self.radius = self._load_config["radius"] - if self._load_config["height"] is not None: - self.height = self._load_config["height"] - if self._load_config["size"] is not None: - self.size = self._load_config["size"] + if self.config.radius is not None: + self.radius = self.config.radius + if self.config.height is not None: + self.height = self.config.height + if self.config.size is not None: + self.size = self.config.size # This step might will perform cloth remeshing if self._prim_type == PrimType.CLOTH. # Therefore, we need to apply size, radius, and height before this to scale the points properly. @@ -150,11 +106,11 @@ def _initialize(self): else: raise ValueError("Prim type must either be PrimType.RIGID or PrimType.CLOTH for loading a primitive object") - visual_geom_prim.color = self._load_config["color"] + visual_geom_prim.color = self.config.rgba[:3] visual_geom_prim.opacity = ( - self._load_config["opacity"].item() - if isinstance(self._load_config["opacity"], th.Tensor) - else self._load_config["opacity"] + self.config.rgba[3].item() + if isinstance(self.config.rgba[3], th.Tensor) + else self.config.rgba[3] ) @property From 7d2d20924df69daf4bc451b13d791446fc086972 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:49:20 -0800 Subject: [PATCH 29/50] feat: Refactor StatefulObject to use structured config with type hints and improved config handling --- omnigibson/configs/base_config.py | 3 ++- omnigibson/objects/stateful_object.py | 10 +++++++++- 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/omnigibson/configs/base_config.py b/omnigibson/configs/base_config.py index ed7c97a26..85d2e9285 100644 --- a/omnigibson/configs/base_config.py +++ b/omnigibson/configs/base_config.py @@ -34,7 +34,8 @@ class ObjectConfig(EntityConfig): @dataclass class StatefulObjectConfig(ObjectConfig): """Configuration for stateful objects""" - pass + abilities: Optional[Dict[str, Dict[str, Any]]] = None + include_default_states: bool = True @dataclass class USDObjectConfig(StatefulObjectConfig): diff --git a/omnigibson/objects/stateful_object.py b/omnigibson/objects/stateful_object.py index 10b7c814b..6761800bc 100644 --- a/omnigibson/objects/stateful_object.py +++ b/omnigibson/objects/stateful_object.py @@ -169,6 +169,14 @@ def states(self): return self._states @property + def config(self) -> StatefulObjectConfig: + """ + Returns: + StatefulObjectConfig: Configuration object for this stateful object + """ + return self._config + + @property def abilities(self): """ Returns: @@ -202,7 +210,7 @@ def prepare_object_states(self): """ states_info = ( {state_type: {"ability": None, "params": dict()} for state_type in get_default_states()} - if self._include_default_states + if self.config.include_default_states else dict() ) From bfbdd3d3c103edf4c57c55ae459b5a8a069ce2dd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:49:52 -0800 Subject: [PATCH 30/50] refactor: Simplify StatefulObject initialization and type hint config parameter --- omnigibson/objects/stateful_object.py | 44 +++++---------------------- 1 file changed, 7 insertions(+), 37 deletions(-) diff --git a/omnigibson/objects/stateful_object.py b/omnigibson/objects/stateful_object.py index 6761800bc..f029e4224 100644 --- a/omnigibson/objects/stateful_object.py +++ b/omnigibson/objects/stateful_object.py @@ -63,59 +63,29 @@ def __call__(self): class StatefulObject(BaseObject): """Objects that support object states.""" - def __init__( - self, - config, - **kwargs, - ): + def __init__(self, config: StatefulObjectConfig): """ Args: - name (str): Name for the object. Names need to be unique per scene - relative_prim_path (None or str): The path relative to its scene prim for this object. If not specified, it defaults to /. - category (str): Category for the object. Defaults to "object". - scale (None or float or 3-array): if specified, sets either the uniform (float) or x,y,z (3-array) scale - for this object. A single number corresponds to uniform scaling along the x,y,z axes, whereas a - 3-array specifies per-axis scaling. - visible (bool): whether to render this object or not in the stage - fixed_base (bool): whether to fix the base of this object or not - visual_only (bool): Whether this object should be visual only (and not collide with any other objects) - kinematic_only (None or bool): Whether this object should be kinematic only (and not get affected by any - collisions). If None, then this value will be set to True if @fixed_base is True and some other criteria - are satisfied (see object_base.py post_load function), else False. - self_collisions (bool): Whether to enable self collisions for this object - prim_type (PrimType): Which type of prim the object is, Valid options are: {PrimType.RIGID, PrimType.CLOTH} - load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for - loading this prim at runtime. - abilities (None or dict): If specified, manually adds specific object states to this object. It should be - a dict in the form of {ability: {param: value}} containing object abilities and parameters to pass to - the object state instance constructor. - include_default_states (bool): whether to include the default object states from @get_default_states - kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing - for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). + config (StatefulObjectConfig): Configuration object for this stateful object """ # Values that will be filled later self._states = None self._emitters = dict() self._visual_states = None self._current_texture_state = None - self._include_default_states = config.include_default_states + self._config = config # Load abilities from taxonomy if needed & possible + self._abilities = {} if config.abilities is None: - abilities = {} taxonomy_class = OBJECT_TAXONOMY.get_synset_from_category(config.category) if taxonomy_class is not None: - abilities = OBJECT_TAXONOMY.get_abilities(taxonomy_class) + self._abilities = OBJECT_TAXONOMY.get_abilities(taxonomy_class) else: - abilities = config.abilities - assert isinstance(abilities, dict), "Object abilities must be in dictionary form." - self._abilities = abilities + self._abilities = config.abilities # Run super init - super().__init__( - config=config, - **kwargs, - ) + super().__init__(config=config) def _post_load(self): # Run super first From bb387d514498dbd0ac702c680355b47971fe34cb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:50:52 -0800 Subject: [PATCH 31/50] feat: Add import for StatefulObjectConfig to resolve undefined name errors --- omnigibson/objects/stateful_object.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/omnigibson/objects/stateful_object.py b/omnigibson/objects/stateful_object.py index f029e4224..e1bb5a8da 100644 --- a/omnigibson/objects/stateful_object.py +++ b/omnigibson/objects/stateful_object.py @@ -4,6 +4,8 @@ import torch as th from bddl.object_taxonomy import ObjectTaxonomy +from omnigibson.configs.base_config import StatefulObjectConfig + import omnigibson as og import omnigibson.lazy as lazy from omnigibson.macros import create_module_macros, gm From 1f060a5b20ee1cf1a020333066f88479ffdc058b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:52:31 -0800 Subject: [PATCH 32/50] refactor: Convert DatasetObject to use structured config with Hydra/OmegaConf --- omnigibson/configs/base_config.py | 1 + omnigibson/objects/dataset_object.py | 105 +++++++++++---------------- 2 files changed, 44 insertions(+), 62 deletions(-) diff --git a/omnigibson/configs/base_config.py b/omnigibson/configs/base_config.py index 85d2e9285..270752ba3 100644 --- a/omnigibson/configs/base_config.py +++ b/omnigibson/configs/base_config.py @@ -50,6 +50,7 @@ class DatasetObjectConfig(StatefulObjectConfig): dataset_type: str = "BEHAVIOR" bounding_box: Optional[List[float]] = None in_rooms: Optional[List[str]] = None + xform_props_pre_loaded: bool = True @dataclass class PrimitiveObjectConfig(StatefulObjectConfig): diff --git a/omnigibson/objects/dataset_object.py b/omnigibson/objects/dataset_object.py index 6c7325fce..22483bfe6 100644 --- a/omnigibson/objects/dataset_object.py +++ b/omnigibson/objects/dataset_object.py @@ -36,27 +36,7 @@ class DatasetObject(USDObject): object's category, e.g., avg dims, bounding boxes, masses, etc. """ - def __init__( - self, - name, - relative_prim_path=None, - category="object", - model=None, - dataset_type=DatasetType.BEHAVIOR, - scale=None, - visible=True, - fixed_base=False, - visual_only=False, - kinematic_only=None, - self_collisions=False, - prim_type=PrimType.RIGID, - load_config=None, - abilities=None, - include_default_states=True, - bounding_box=None, - in_rooms=None, - **kwargs, - ): + def __init__(self, config: DatasetObjectConfig): """ Args: name (str): Name for the object. Names need to be unique per scene @@ -97,60 +77,61 @@ def __init__( for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). """ # Store variables - if isinstance(in_rooms, str): - assert "," not in in_rooms - self._in_rooms = [in_rooms] if isinstance(in_rooms, str) else in_rooms + if isinstance(config.in_rooms, str): + assert "," not in config.in_rooms + self._in_rooms = [config.in_rooms] if isinstance(config.in_rooms, str) else config.in_rooms # Make sure only one of bounding_box and scale are specified - if bounding_box is not None and scale is not None: - raise Exception("You cannot define both scale and bounding box size for an DatasetObject") + if config.bounding_box is not None and config.scale is not None: + raise Exception("You cannot define both scale and bounding box size for a DatasetObject") - # Add info to load config - load_config = dict() if load_config is None else load_config - load_config["bounding_box"] = bounding_box - load_config["dataset_type"] = dataset_type - # All DatasetObjects should have xform properties pre-loaded - load_config["xform_props_pre_loaded"] = True + # Store config + self._config = config # Infer the correct usd path to use - if model is None: - available_models = get_all_object_category_models(category=category) - assert len(available_models) > 0, f"No available models found for category {category}!" - model = random.choice(available_models) + if config.model is None: + available_models = get_all_object_category_models(category=config.category) + assert len(available_models) > 0, f"No available models found for category {config.category}!" + config.model = random.choice(available_models) # If the model is in BAD_CLOTH_MODELS, raise an error for now -- this is a model that's unstable and needs to be fixed # TODO: Remove this once the asset is fixed! from omnigibson.utils.bddl_utils import BAD_CLOTH_MODELS - if prim_type == PrimType.CLOTH and model in BAD_CLOTH_MODELS.get(category, dict()): + if config.prim_type == PrimType.CLOTH and config.model in BAD_CLOTH_MODELS.get(config.category, dict()): raise ValueError( - f"Cannot create cloth object category: {category}, model: {model} because it is " + f"Cannot create cloth object category: {config.category}, model: {config.model} because it is " f"currently broken ): This will be fixed in the next release!" ) - self._model = model - usd_path = self.get_usd_path(category=category, model=model, dataset_type=dataset_type) + self._model = config.model + usd_path = self.get_usd_path( + category=config.category, + model=config.model, + dataset_type=DatasetType[config.dataset_type], + ) - # Run super init - super().__init__( - relative_prim_path=relative_prim_path, + # Create USDObjectConfig from our config + usd_config = USDObjectConfig( + name=config.name, + relative_prim_path=config.relative_prim_path, + category=config.category, usd_path=usd_path, - encrypted=dataset_type == DatasetType.BEHAVIOR, - name=name, - category=category, - scale=scale, - visible=visible, - fixed_base=fixed_base, - visual_only=visual_only, - kinematic_only=kinematic_only, - self_collisions=self_collisions, - prim_type=prim_type, - include_default_states=include_default_states, - load_config=load_config, - abilities=abilities, - **kwargs, + encrypted=config.dataset_type == "BEHAVIOR", + scale=config.scale, + visible=config.visible, + fixed_base=config.fixed_base, + visual_only=config.visual_only, + kinematic_only=config.kinematic_only, + self_collisions=config.self_collisions, + prim_type=config.prim_type, + abilities=config.abilities, + include_default_states=config.include_default_states, ) + # Run super init + super().__init__(config=usd_config) + @classmethod def get_usd_path(cls, category, model, dataset_type=DatasetType.BEHAVIOR): """ @@ -233,20 +214,20 @@ def recursive_light_update(child_prim): def _post_load(self): # If manual bounding box is specified, scale based on ratio between that and the native bbox - if self._load_config["bounding_box"] is not None: + if self._config.bounding_box is not None: scale = th.ones(3) valid_idxes = self.native_bbox > 1e-4 scale[valid_idxes] = ( - th.tensor(self._load_config["bounding_box"])[valid_idxes] / self.native_bbox[valid_idxes] + th.tensor(self._config.bounding_box)[valid_idxes] / self.native_bbox[valid_idxes] ) else: - scale = th.ones(3) if self._load_config["scale"] is None else self._load_config["scale"] + scale = th.ones(3) if self._config.scale is None else self._config.scale # Assert that the scale does not have too small dimensions assert th.all(th.tensor(scale) > 1e-4), f"Scale of {self.name} is too small: {scale}" - # Set this scale in the load config -- it will automatically scale the object during self.initialize() - self._load_config["scale"] = scale + # Update config scale + self._config.scale = scale # Run super last super()._post_load() From 0d96887d67c1b532c3d684668844403cc48a7343 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:53:02 -0800 Subject: [PATCH 33/50] refactor: Add imports for DatasetObjectConfig and USDObjectConfig --- omnigibson/objects/dataset_object.py | 1 + 1 file changed, 1 insertion(+) diff --git a/omnigibson/objects/dataset_object.py b/omnigibson/objects/dataset_object.py index 22483bfe6..b91c9011e 100644 --- a/omnigibson/objects/dataset_object.py +++ b/omnigibson/objects/dataset_object.py @@ -6,6 +6,7 @@ import torch as th import omnigibson.lazy as lazy +from omnigibson.configs.base_config import DatasetObjectConfig, USDObjectConfig import omnigibson.utils.transform_utils as T from omnigibson.macros import create_module_macros, gm from omnigibson.objects.usd_object import USDObject From d84e2a8e47145ee3249151f72ac69f5d533e351e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:54:17 -0800 Subject: [PATCH 34/50] refactor: Convert USDObject to use structured config with proper config access --- omnigibson/objects/usd_object.py | 59 ++++++++------------------------ 1 file changed, 15 insertions(+), 44 deletions(-) diff --git a/omnigibson/objects/usd_object.py b/omnigibson/objects/usd_object.py index 30007c8ca..c939fdedd 100644 --- a/omnigibson/objects/usd_object.py +++ b/omnigibson/objects/usd_object.py @@ -13,46 +13,17 @@ class USDObject(StatefulObject): or more links and joints. They may or may not be passive. """ - def __init__( - self, - config, - **kwargs, - ): + def __init__(self, config: USDObjectConfig): """ Args: - name (str): Name for the object. Names need to be unique per scene - usd_path (str): global path to the USD file to load - encrypted (bool): whether this file is encrypted (and should therefore be decrypted) or not - relative_prim_path (None or str): The path relative to its scene prim for this object. If not specified, it defaults to /. - category (str): Category for the object. Defaults to "object". - scale (None or float or 3-array): if specified, sets either the uniform (float) or x,y,z (3-array) scale - for this object. A single number corresponds to uniform scaling along the x,y,z axes, whereas a - 3-array specifies per-axis scaling. - visible (bool): whether to render this object or not in the stage - fixed_base (bool): whether to fix the base of this object or not - visual_only (bool): Whether this object should be visual only (and not collide with any other objects) - kinematic_only (None or bool): Whether this object should be kinematic only (and not get affected by any - collisions). If None, then this value will be set to True if @fixed_base is True and some other criteria - are satisfied (see object_base.py post_load function), else False. - self_collisions (bool): Whether to enable self collisions for this object - prim_type (PrimType): Which type of prim the object is, Valid options are: {PrimType.RIGID, PrimType.CLOTH} - load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for - loading this prim at runtime. - abilities (None or dict): If specified, manually adds specific object states to this object. It should be - a dict in the form of {ability: {param: value}} containing object abilities and parameters to pass to - the object state instance constructor. - include_default_states (bool): whether to include the default object states from @get_default_states - kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing - for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). - Note that this base object does NOT pass kwargs down into the Prim-type super() classes, and we assume - that kwargs are only shared between all SUBclasses (children), not SUPERclasses (parents). + config (USDObjectConfig): Configuration object containing all relevant parameters for + initializing this USD object. See the USDObjectConfig dataclass for specific parameters. """ - self._usd_path = config.usd_path - self._encrypted = config.encrypted - super().__init__( - config=config, - **kwargs, - ) + # Store the config + self._config = config + + # Initialize super + super().__init__(config=config) def prebuild(self, stage): # Load the object into the given USD stage @@ -85,16 +56,16 @@ def _load(self): """ Load the object into pybullet and set it to the correct pose """ - usd_path = self._usd_path - if self._encrypted: + usd_path = self._config.usd_path + if self._config.encrypted: # Create a temporary file to store the decrytped asset, load it, and then delete it - encrypted_filename = self._usd_path.replace(".usd", ".encrypted.usd") - decrypted_fd, usd_path = tempfile.mkstemp(os.path.basename(self._usd_path), dir=og.tempdir) + encrypted_filename = self._config.usd_path.replace(".usd", ".encrypted.usd") + decrypted_fd, usd_path = tempfile.mkstemp(os.path.basename(self._config.usd_path), dir=og.tempdir) decrypt_file(encrypted_filename, usd_path) prim = add_asset_to_stage(asset_path=usd_path, prim_path=self.prim_path) - if self._encrypted: + if self._config.encrypted: os.close(decrypted_fd) # On Windows, Isaac Sim won't let go of the file until the prim is removed, so we can't delete it. if os.name == "posix": @@ -107,6 +78,6 @@ def usd_path(self): """ Returns: str: absolute path to this model's USD file. By default, this is the loaded usd path - passed in as an argument + from the config """ - return self._usd_path + return self._config.usd_path From f077cc8e911a8fc39e769d556275d5cfecabbea1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:54:28 -0800 Subject: [PATCH 35/50] refactor: Update USDObject to use structured USDObjectConfig --- omnigibson/objects/usd_object.py | 1 + 1 file changed, 1 insertion(+) diff --git a/omnigibson/objects/usd_object.py b/omnigibson/objects/usd_object.py index c939fdedd..c50f1e375 100644 --- a/omnigibson/objects/usd_object.py +++ b/omnigibson/objects/usd_object.py @@ -2,6 +2,7 @@ import tempfile import omnigibson as og +from omnigibson.configs.base_config import USDObjectConfig from omnigibson.objects.stateful_object import StatefulObject from omnigibson.utils.asset_utils import decrypt_file from omnigibson.utils.usd_utils import add_asset_to_stage From aec3baf064cc1a31f99caa38c6ef496554f5c2e0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:55:40 -0800 Subject: [PATCH 36/50] refactor: Convert LightObject to use structured config with direct config access --- omnigibson/objects/light_object.py | 62 ++++++++++-------------------- 1 file changed, 20 insertions(+), 42 deletions(-) diff --git a/omnigibson/objects/light_object.py b/omnigibson/objects/light_object.py index b4ea12917..4ae251ff8 100644 --- a/omnigibson/objects/light_object.py +++ b/omnigibson/objects/light_object.py @@ -26,50 +26,22 @@ class LightObject(StatefulObject): "Sphere", } - def __init__( - self, - config, - **kwargs, - ): + def __init__(self, config: LightObjectConfig): """ Args: - name (str): Name for the object. Names need to be unique per scene - light_type (str): Type of light to create. Valid options are LIGHT_TYPES - relative_prim_path (None or str): The path relative to its scene prim for this object. If not specified, it defaults to /. - category (str): Category for the object. Defaults to "object". - scale (None or float or 3-array): if specified, sets either the uniform (float) or x,y,z (3-array) scale - for this object. A single number corresponds to uniform scaling along the x,y,z axes, whereas a - 3-array specifies per-axis scaling. - fixed_base (bool): whether to fix the base of this object or not - load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for - loading this prim at runtime. - abilities (None or dict): If specified, manually adds specific object states to this object. It should be - a dict in the form of {ability: {param: value}} containing object abilities and parameters to pass to - the object state instance constructor. - include_default_states (bool): whether to include the default object states from @get_default_states - radius (float): Radius for this light. - intensity (float): Intensity for this light. - kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing - for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). + config (LightObjectConfig): Configuration object containing all parameters for this light object """ # Make sure primitive type is valid assert_valid_key(key=config.light_type, valid_keys=self.LIGHT_TYPES, name="light_type") - self.light_type = config.light_type - - # Compose load config - load_config = dict() if config.load_config is None else config.load_config - load_config["scale"] = config.scale - load_config["intensity"] = config.intensity - load_config["radius"] = config.radius if config.light_type in {"Cylinder", "Disk", "Sphere"} else None - + + # Store the config + self._config = config + # Other attributes to be filled in at runtime self._light_link = None # Run super method - super().__init__( - config=config, - **kwargs, - ) + super().__init__(config=config) def _load(self): # Define XForm and base link for this light @@ -98,13 +70,12 @@ def _post_load(self): # Apply Shaping API and set default cone angle attribute lazy.pxr.UsdLux.ShapingAPI.Apply(self._light_link.prim).GetShapingConeAngleAttr().Set(180.0) - # Optionally set the intensity - if self._load_config.get("intensity", None) is not None: - self.intensity = self._load_config["intensity"] - - # Optionally set the radius - if self._load_config.get("radius", None) is not None: - self.radius = self._load_config["radius"] + # Set the intensity and radius from config + self.intensity = self._config.intensity + + # Only set radius for applicable light types + if self._config.light_type in {"Cylinder", "Disk", "Sphere"}: + self.radius = self._config.radius def _initialize(self): # Run super @@ -206,3 +177,10 @@ def texture_file_path(self, texture_file_path): texture_file_path (str): path of texture file that should be used for this light """ self._light_link.set_attribute("inputs:texture:file", lazy.pxr.Sdf.AssetPath(texture_file_path)) + @property + def light_type(self): + """ + Returns: + str: Type of light + """ + return self._config.light_type From 71560ba8f55cb7b9a400ec6ac535e58eab37fed3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:56:02 -0800 Subject: [PATCH 37/50] refactor: Update LightObject to use structured config with import --- omnigibson/objects/light_object.py | 1 + 1 file changed, 1 insertion(+) diff --git a/omnigibson/objects/light_object.py b/omnigibson/objects/light_object.py index 4ae251ff8..2b9b99640 100644 --- a/omnigibson/objects/light_object.py +++ b/omnigibson/objects/light_object.py @@ -3,6 +3,7 @@ import omnigibson as og import omnigibson.lazy as lazy from omnigibson.objects.stateful_object import StatefulObject +from omnigibson.configs.base_config import LightObjectConfig from omnigibson.prims.xform_prim import XFormPrim from omnigibson.utils.python_utils import assert_valid_key from omnigibson.utils.ui_utils import create_module_logger From 536903210ccf566ee9bcbb7ec4b5a928e773f662 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:57:28 -0800 Subject: [PATCH 38/50] refactor: Migrate ControllableObject to use structured Hydra/OmegaConf configs --- omnigibson/configs/base_config.py | 4 +- omnigibson/objects/controllable_object.py | 56 +++++------------------ 2 files changed, 13 insertions(+), 47 deletions(-) diff --git a/omnigibson/configs/base_config.py b/omnigibson/configs/base_config.py index 270752ba3..ba6a9b312 100644 --- a/omnigibson/configs/base_config.py +++ b/omnigibson/configs/base_config.py @@ -68,11 +68,11 @@ class LightObjectConfig(StatefulObjectConfig): radius: float = 1.0 intensity: float = 50000.0 -@dataclass +@dataclass class ControllableObjectConfig(StatefulObjectConfig): """Configuration for controllable objects""" control_freq: Optional[float] = None - controller_config: Optional[Dict[str, Any]] = None action_type: str = "continuous" action_normalize: bool = True reset_joint_pos: Optional[List[float]] = None + controllers: Dict[str, ControllerConfig] = field(default_factory=dict) diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index ad96d7f10..49f003b4f 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -29,25 +29,7 @@ class ControllableObject(BaseObject): e.g.: a conveyor belt or a robot agent """ - def __init__( - self, - name, - relative_prim_path=None, - category="object", - scale=None, - visible=True, - fixed_base=False, - visual_only=False, - self_collisions=False, - prim_type=PrimType.RIGID, - load_config=None, - control_freq=None, - controller_config=None, - action_type="continuous", - action_normalize=True, - reset_joint_pos=None, - **kwargs, - ): + def __init__(self, config, **kwargs): """ Args: name (str): Name for the object. Names need to be unique per scene @@ -77,15 +59,14 @@ def __init__( kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). """ - # Store inputs - self._control_freq = control_freq - self._controller_config = controller_config - self._reset_joint_pos = None if reset_joint_pos is None else th.tensor(reset_joint_pos, dtype=th.float) + # Store inputs from config + self._control_freq = config.control_freq + self._reset_joint_pos = None if config.reset_joint_pos is None else th.tensor(config.reset_joint_pos, dtype=th.float) # Make sure action type is valid, and also save - assert_valid_key(key=action_type, valid_keys={"discrete", "continuous"}, name="action type") - self._action_type = action_type - self._action_normalize = action_normalize + assert_valid_key(key=config.action_type, valid_keys={"discrete", "continuous"}, name="action type") + self._action_type = config.action_type + self._action_normalize = config.action_normalize # Store internal placeholders that will be filled in later self._dof_to_joints = None # dict that will map DOF indices to JointPrims @@ -112,20 +93,8 @@ def __init__( # If prim path is not specified, set it to the default path, but prepend controllable. relative_prim_path = f"/controllable__{class_name}__{name}" - # Run super init - super().__init__( - relative_prim_path=relative_prim_path, - name=name, - category=category, - scale=scale, - visible=visible, - fixed_base=fixed_base, - visual_only=visual_only, - self_collisions=self_collisions, - prim_type=prim_type, - load_config=load_config, - **kwargs, - ) + # Run super init with config + super().__init__(config=config, **kwargs) def _initialize(self): # Assert that the prim path matches ControllableObjectViewAPI's expected format @@ -224,11 +193,8 @@ def _load_controllers(self): Stores created controllers as dictionary mapping controller names to specific controller instances used by this object. """ - # Generate the controller config - self._controller_config = self._generate_controller_config(custom_config=self._controller_config) - - # We copy the controller config here because we add/remove some keys in-place that shouldn't persist - _controller_config = deepcopy(self._controller_config) + # Store controller configs from structured config + self._controller_config = config.controllers # Store dof idx mapping to dof name self.dof_names_ordered = list(self._joints.keys()) From 3d76e40e29566351e7bdb14539a207cc1840d542 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:58:04 -0800 Subject: [PATCH 39/50] The changes look good. I'll generate a concise commit message for these modifications: refactor: Update ControllableObject to use structured config for controllers --- omnigibson/configs/base_config.py | 1 + omnigibson/objects/controllable_object.py | 18 +++++++++--------- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/omnigibson/configs/base_config.py b/omnigibson/configs/base_config.py index ba6a9b312..2e0509e70 100644 --- a/omnigibson/configs/base_config.py +++ b/omnigibson/configs/base_config.py @@ -1,6 +1,7 @@ from dataclasses import dataclass, field from typing import Optional, List, Dict, Any from omegaconf import MISSING +from omnigibson.configs.robot_config import ControllerConfig @dataclass class BaseConfig: diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index 49f003b4f..5a162415b 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -76,22 +76,22 @@ def __init__(self, config, **kwargs): self._control_enabled = True class_name = self.__class__.__name__.lower() - if relative_prim_path: + if config.relative_prim_path: # If prim path is specified, assert that the last element starts with the right prefix to ensure that # the object will be included in the ControllableObjectViewAPI. - assert relative_prim_path.split("/")[-1].startswith(f"controllable__{class_name}__"), ( + assert config.relative_prim_path.split("/")[-1].startswith(f"controllable__{class_name}__"), ( "If relative_prim_path is specified, the last element of the path must look like " f"'controllable__{class_name}__robotname' where robotname can be an arbitrary " "string containing no double underscores." ) - assert relative_prim_path.split("/")[-1].count("__") == 2, ( + assert config.relative_prim_path.split("/")[-1].count("__") == 2, ( "If relative_prim_path is specified, the last element of the path must look like " f"'controllable__{class_name}__robotname' where robotname can be an arbitrary " "string containing no double underscores." ) else: # If prim path is not specified, set it to the default path, but prepend controllable. - relative_prim_path = f"/controllable__{class_name}__{name}" + config.relative_prim_path = f"/controllable__{class_name}__{config.name}" # Run super init with config super().__init__(config=config, **kwargs) @@ -194,7 +194,7 @@ def _load_controllers(self): instances used by this object. """ # Store controller configs from structured config - self._controller_config = config.controllers + self._controller_config = self.config.controllers # Store dof idx mapping to dof name self.dof_names_ordered = list(self._joints.keys()) @@ -207,8 +207,8 @@ def _load_controllers(self): subsume_names = set() for name in self._raw_controller_order: # Make sure we have the valid controller name specified - assert_valid_key(key=name, valid_keys=_controller_config, name="controller name") - cfg = _controller_config[name] + assert_valid_key(key=name, valid_keys=self._controller_config, name="controller name") + cfg = self._controller_config[name] subsume_controllers = cfg.pop("subsume_controllers", []) # If this controller subsumes other controllers, it cannot be subsumed by another controller # (i.e.: we don't allow nested / cyclical subsuming) @@ -232,11 +232,11 @@ def _load_controllers(self): # If this controller is subsumed by another controller, simply skip it if name in subsume_names: continue - cfg = _controller_config[name] + cfg = self._controller_config[name] # If we subsume other controllers, prepend the subsumed' dof idxs to this controller's idxs if name in controller_subsumes: for subsumed_name in controller_subsumes[name]: - subsumed_cfg = _controller_config[subsumed_name] + subsumed_cfg = self._controller_config[subsumed_name] cfg["dof_idx"] = th.concatenate([subsumed_cfg["dof_idx"], cfg["dof_idx"]]) # If we're using normalized action space, override the inputs for all controllers From 528e49debc2920cdc40f341f00f884d1a9c81d4a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 15:59:59 -0800 Subject: [PATCH 40/50] refactor: Migrate ControllableObject to use structured configs and remove manual config handling --- omnigibson/objects/controllable_object.py | 102 +++++++--------------- 1 file changed, 32 insertions(+), 70 deletions(-) diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index 5a162415b..640f6d2f1 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -29,44 +29,13 @@ class ControllableObject(BaseObject): e.g.: a conveyor belt or a robot agent """ - def __init__(self, config, **kwargs): + def __init__(self, config): """ Args: - name (str): Name for the object. Names need to be unique per scene - relative_prim_path (None or str): The path relative to its scene prim for this object. If not specified, it defaults to /. - category (str): Category for the object. Defaults to "object". - scale (None or float or 3-array): if specified, sets either the uniform (float) or x,y,z (3-array) scale - for this object. A single number corresponds to uniform scaling along the x,y,z axes, whereas a - 3-array specifies per-axis scaling. - visible (bool): whether to render this object or not in the stage - fixed_base (bool): whether to fix the base of this object or not - visual_only (bool): Whether this object should be visual only (and not collide with any other objects) - self_collisions (bool): Whether to enable self collisions for this object - prim_type (PrimType): Which type of prim the object is, Valid options are: {PrimType.RIGID, PrimType.CLOTH} - load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for - loading this prim at runtime. - control_freq (float): control frequency (in Hz) at which to control the object. If set to be None, - we will automatically set the control frequency to be at the render frequency by default. - controller_config (None or dict): nested dictionary mapping controller name(s) to specific controller - configurations for this object. This will override any default values specified by this class. - action_type (str): one of {discrete, continuous} - what type of action space to use - action_normalize (bool): whether to normalize inputted actions. This will override any default values - specified by this class. - reset_joint_pos (None or n-array): if specified, should be the joint positions that the object should - be set to during a reset. If None (default), self._default_joint_pos will be used instead. - Note that _default_joint_pos are hardcoded & precomputed, and thus should not be modified by the user. - Set this value instead if you want to initialize the object with a different rese joint position. - kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing - for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). - """ - # Store inputs from config - self._control_freq = config.control_freq - self._reset_joint_pos = None if config.reset_joint_pos is None else th.tensor(config.reset_joint_pos, dtype=th.float) - - # Make sure action type is valid, and also save - assert_valid_key(key=config.action_type, valid_keys={"discrete", "continuous"}, name="action type") - self._action_type = config.action_type - self._action_normalize = config.action_normalize + config (ControllableObjectConfig): Configuration object for this controllable object + """ + # Store config + self._config = config # Store internal placeholders that will be filled in later self._dof_to_joints = None # dict that will map DOF indices to JointPrims @@ -75,6 +44,10 @@ def __init__(self, config, **kwargs): self.dof_names_ordered = None self._control_enabled = True + # Make sure action type is valid + assert_valid_key(key=config.action_type, valid_keys={"discrete", "continuous"}, name="action type") + + # Handle prim path class_name = self.__class__.__name__.lower() if config.relative_prim_path: # If prim path is specified, assert that the last element starts with the right prefix to ensure that @@ -93,8 +66,8 @@ def __init__(self, config, **kwargs): # If prim path is not specified, set it to the default path, but prepend controllable. config.relative_prim_path = f"/controllable__{class_name}__{config.name}" - # Run super init with config - super().__init__(config=config, **kwargs) + # Run super init + super().__init__(config=config) def _initialize(self): # Assert that the prim path matches ControllableObjectViewAPI's expected format @@ -193,39 +166,27 @@ def _load_controllers(self): Stores created controllers as dictionary mapping controller names to specific controller instances used by this object. """ - # Store controller configs from structured config - self._controller_config = self.config.controllers - # Store dof idx mapping to dof name self.dof_names_ordered = list(self._joints.keys()) # Initialize controllers to create self._controllers = dict() - # Keep track of any controllers that are subsumed by other controllers - # We will not instantiate subsumed controllers - controller_subsumes = dict() # Maps independent controller name to list of subsumed controllers - subsume_names = set() + + # Process controller configs from structured config for name in self._raw_controller_order: # Make sure we have the valid controller name specified - assert_valid_key(key=name, valid_keys=self._controller_config, name="controller name") - cfg = self._controller_config[name] - subsume_controllers = cfg.pop("subsume_controllers", []) - # If this controller subsumes other controllers, it cannot be subsumed by another controller - # (i.e.: we don't allow nested / cyclical subsuming) - if len(subsume_controllers) > 0: - assert ( - name not in subsume_names - ), f"Controller {name} subsumes other controllers, and therefore cannot be subsumed by another controller!" - controller_subsumes[name] = subsume_controllers - for subsume_name in subsume_controllers: - # Make sure it doesn't already exist -- a controller should only be subsumed by up to one other - assert ( - subsume_name not in subsume_names - ), f"Controller {subsume_name} cannot be subsumed by more than one other controller!" - assert ( - subsume_name not in controller_subsumes - ), f"Controller {name} subsumes other controllers, and therefore cannot be subsumed by another controller!" - subsume_names.add(subsume_name) + assert_valid_key(key=name, valid_keys=self.config.controllers, name="controller name") + + # Create the controller from structured config + controller = create_controller(**cb.from_torch_recursive(self.config.controllers[name])) + + # Verify the controller's DOFs can all be driven + for idx in controller.dof_idx: + assert self._joints[ + self.dof_names_ordered[idx] + ].driven, "Controllers should only control driveable joints!" + + self._controllers[name] = controller # Loop over all controllers, in the order corresponding to @action dim for name in self._raw_controller_order: @@ -319,15 +280,16 @@ def _generate_controller_config(self, custom_config=None): return controller_config - def reload_controllers(self, controller_config=None): + def reload_controllers(self, controller_configs=None): """ - Reloads controllers based on the specified new @controller_config + Reloads controllers based on the specified new controller configs Args: - controller_config (None or Dict[str, ...]): nested dictionary mapping controller name(s) to specific - controller configurations for this object. This will override any default values specified by this class. + controller_configs (None or Dict[str, ControllerConfig]): Mapping of controller names to their configs. + If None, will use the existing controller configs. """ - self._controller_config = {} if controller_config is None else controller_config + if controller_configs is not None: + self.config.controllers = controller_configs # (Re-)load controllers self._load_controllers() @@ -335,7 +297,7 @@ def reload_controllers(self, controller_config=None): # (Re-)create the action space self._action_space = ( self._create_discrete_action_space() - if self._action_type == "discrete" + if self.config.action_type == "discrete" else self._create_continuous_action_space() ) From a35a1bfe09e0c5e6114827edb421c4711fe5a48f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:00:27 -0800 Subject: [PATCH 41/50] fix: Remove unused subsume controller code and update controller config handling --- omnigibson/objects/controllable_object.py | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index 640f6d2f1..5a4387b24 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -190,18 +190,12 @@ def _load_controllers(self): # Loop over all controllers, in the order corresponding to @action dim for name in self._raw_controller_order: - # If this controller is subsumed by another controller, simply skip it - if name in subsume_names: - continue - cfg = self._controller_config[name] - # If we subsume other controllers, prepend the subsumed' dof idxs to this controller's idxs - if name in controller_subsumes: - for subsumed_name in controller_subsumes[name]: - subsumed_cfg = self._controller_config[subsumed_name] - cfg["dof_idx"] = th.concatenate([subsumed_cfg["dof_idx"], cfg["dof_idx"]]) - + # Make sure we have the valid controller name specified + assert_valid_key(key=name, valid_keys=self.config.controllers, name="controller name") + # If we're using normalized action space, override the inputs for all controllers - if self._action_normalize: + cfg = dict(self.config.controllers[name]) + if self.config.action_normalize: cfg["command_input_limits"] = "default" # default is normalized (-1, 1) # Create the controller From fd36ce05a0465e7538ec55f36a3ca00eef5e18da Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:01:36 -0800 Subject: [PATCH 42/50] refactor: Simplify ControllableObject config handling and controller initialization --- omnigibson/objects/controllable_object.py | 64 +++++++++-------------- 1 file changed, 25 insertions(+), 39 deletions(-) diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index 5a4387b24..5992cc9e4 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -34,9 +34,6 @@ def __init__(self, config): Args: config (ControllableObjectConfig): Configuration object for this controllable object """ - # Store config - self._config = config - # Store internal placeholders that will be filled in later self._dof_to_joints = None # dict that will map DOF indices to JointPrims self._last_action = None @@ -66,7 +63,7 @@ def __init__(self, config): # If prim path is not specified, set it to the default path, but prepend controllable. config.relative_prim_path = f"/controllable__{class_name}__{config.name}" - # Run super init + # Run super init with config super().__init__(config=config) def _initialize(self): @@ -177,8 +174,13 @@ def _load_controllers(self): # Make sure we have the valid controller name specified assert_valid_key(key=name, valid_keys=self.config.controllers, name="controller name") + # Get controller config and override input limits if using normalized actions + controller_cfg = self.config.controllers[name] + if self.config.action_normalize: + controller_cfg.command_input_limits = "default" # default is normalized (-1, 1) + # Create the controller from structured config - controller = create_controller(**cb.from_torch_recursive(self.config.controllers[name])) + controller = create_controller(**cb.from_torch_recursive(controller_cfg)) # Verify the controller's DOFs can all be driven for idx in controller.dof_idx: @@ -187,25 +189,7 @@ def _load_controllers(self): ].driven, "Controllers should only control driveable joints!" self._controllers[name] = controller - - # Loop over all controllers, in the order corresponding to @action dim - for name in self._raw_controller_order: - # Make sure we have the valid controller name specified - assert_valid_key(key=name, valid_keys=self.config.controllers, name="controller name") - # If we're using normalized action space, override the inputs for all controllers - cfg = dict(self.config.controllers[name]) - if self.config.action_normalize: - cfg["command_input_limits"] = "default" # default is normalized (-1, 1) - - # Create the controller - controller = create_controller(**cb.from_torch_recursive(cfg)) - # Verify the controller's DOFs can all be driven - for idx in controller.dof_idx: - assert self._joints[ - self.dof_names_ordered[idx] - ].driven, "Controllers should only control driveable joints!" - self._controllers[name] = controller self.update_controller_mode() def update_controller_mode(self): @@ -251,26 +235,28 @@ def _generate_controller_config(self, custom_config=None): specified in @custom_config Args: - custom_config (None or Dict[str, ...]): nested dictionary mapping controller name(s) to specific custom - controller configurations for this object. This will override any default values specified by this class + custom_config (None or Dict[str, ControllerConfig]): Mapping of controller names to their configs. + If specified, will override the default controller configs. Returns: - dict: Fully-populated nested dictionary mapping controller name(s) to specific controller configurations for - this object + Dict[str, ControllerConfig]: Mapping of controller names to their configs """ - controller_config = {} if custom_config is None else deepcopy(custom_config) - - # Update the configs + # Start with default controller configs + controller_config = {} + + # For each controller group for group in self._raw_controller_order: - group_controller_name = ( - controller_config[group]["name"] - if group in controller_config and "name" in controller_config[group] - else self._default_controllers[group] - ) - controller_config[group] = merge_nested_dicts( - base_dict=self._default_controller_config[group][group_controller_name], - extra_dict=controller_config.get(group, {}), - ) + # Get default controller type for this group + default_controller = self._default_controllers[group] + + # Get default config for this controller type + default_config = self._default_controller_config[group][default_controller] + + # Override with custom config if specified + if custom_config is not None and group in custom_config: + controller_config[group] = custom_config[group] + else: + controller_config[group] = default_config return controller_config From 39cc75ac352aac1afd6e7f4046c25c272b4ff5aa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:02:26 -0800 Subject: [PATCH 43/50] refactor: Improve structured config handling in ControllableObject --- omnigibson/objects/controllable_object.py | 29 ++++++++++++++++------- 1 file changed, 20 insertions(+), 9 deletions(-) diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index 5992cc9e4..8ff9d4b24 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -29,11 +29,14 @@ class ControllableObject(BaseObject): e.g.: a conveyor belt or a robot agent """ - def __init__(self, config): + def __init__(self, config: ControllableObjectConfig): """ Args: config (ControllableObjectConfig): Configuration object for this controllable object """ + # Store config + self.config = config + # Store internal placeholders that will be filled in later self._dof_to_joints = None # dict that will map DOF indices to JointPrims self._last_action = None @@ -42,29 +45,29 @@ def __init__(self, config): self._control_enabled = True # Make sure action type is valid - assert_valid_key(key=config.action_type, valid_keys={"discrete", "continuous"}, name="action type") + assert_valid_key(key=self.config.action_type, valid_keys={"discrete", "continuous"}, name="action type") # Handle prim path class_name = self.__class__.__name__.lower() - if config.relative_prim_path: + if self.config.relative_prim_path: # If prim path is specified, assert that the last element starts with the right prefix to ensure that # the object will be included in the ControllableObjectViewAPI. - assert config.relative_prim_path.split("/")[-1].startswith(f"controllable__{class_name}__"), ( + assert self.config.relative_prim_path.split("/")[-1].startswith(f"controllable__{class_name}__"), ( "If relative_prim_path is specified, the last element of the path must look like " f"'controllable__{class_name}__robotname' where robotname can be an arbitrary " "string containing no double underscores." ) - assert config.relative_prim_path.split("/")[-1].count("__") == 2, ( + assert self.config.relative_prim_path.split("/")[-1].count("__") == 2, ( "If relative_prim_path is specified, the last element of the path must look like " f"'controllable__{class_name}__robotname' where robotname can be an arbitrary " "string containing no double underscores." ) else: # If prim path is not specified, set it to the default path, but prepend controllable. - config.relative_prim_path = f"/controllable__{class_name}__{config.name}" + self.config.relative_prim_path = f"/controllable__{class_name}__{self.config.name}" # Run super init with config - super().__init__(config=config) + super().__init__(config=self.config) def _initialize(self): # Assert that the prim path matches ControllableObjectViewAPI's expected format @@ -180,7 +183,7 @@ def _load_controllers(self): controller_cfg.command_input_limits = "default" # default is normalized (-1, 1) # Create the controller from structured config - controller = create_controller(**cb.from_torch_recursive(controller_cfg)) + controller = create_controller(name=controller_cfg.name, **cb.from_torch_recursive(controller_cfg)) # Verify the controller's DOFs can all be driven for idx in controller.dof_idx: @@ -269,7 +272,15 @@ def reload_controllers(self, controller_configs=None): If None, will use the existing controller configs. """ if controller_configs is not None: - self.config.controllers = controller_configs + # Create new structured configs from the input + from omnigibson.configs.robot_config import ControllerConfig + new_controllers = {} + for name, cfg in controller_configs.items(): + if isinstance(cfg, dict): + new_controllers[name] = ControllerConfig(**cfg) + else: + new_controllers[name] = cfg + self.config.controllers = new_controllers # (Re-)load controllers self._load_controllers() From e284b567de52189aef1da65974fea4f2f906790e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:02:54 -0800 Subject: [PATCH 44/50] feat: Add import for ControllableObjectConfig in controllable_object.py --- omnigibson/objects/controllable_object.py | 1 + 1 file changed, 1 insertion(+) diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index 8ff9d4b24..6abb5a41e 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -17,6 +17,7 @@ from omnigibson.utils.python_utils import CachedFunctions, assert_valid_key, merge_nested_dicts from omnigibson.utils.ui_utils import create_module_logger from omnigibson.utils.usd_utils import ControllableObjectViewAPI +from omnigibson.configs.base_config import ControllableObjectConfig # Create module logger log = create_module_logger(module_name=__name__) From e5515f62a3e591ddcf8d8a24c8f210d5ce0f9409 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:06:00 -0800 Subject: [PATCH 45/50] feat: Refactor object classes to use config object directly This commit updates multiple object classes to consistently store and reference the full config object, removing redundant attribute storage and improving config handling across the codebase. --- omnigibson/objects/controllable_object.py | 30 +++++++++++------------ omnigibson/objects/dataset_object.py | 9 +++---- omnigibson/objects/light_object.py | 4 +-- omnigibson/objects/primitive_object.py | 10 +++++--- omnigibson/objects/usd_object.py | 2 +- 5 files changed, 26 insertions(+), 29 deletions(-) diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index 6abb5a41e..f679fece2 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -35,40 +35,38 @@ def __init__(self, config: ControllableObjectConfig): Args: config (ControllableObjectConfig): Configuration object for this controllable object """ - # Store config - self.config = config - - # Store internal placeholders that will be filled in later - self._dof_to_joints = None # dict that will map DOF indices to JointPrims - self._last_action = None - self._controllers = None - self.dof_names_ordered = None - self._control_enabled = True - # Make sure action type is valid - assert_valid_key(key=self.config.action_type, valid_keys={"discrete", "continuous"}, name="action type") + assert_valid_key(key=config.action_type, valid_keys={"discrete", "continuous"}, name="action type") # Handle prim path class_name = self.__class__.__name__.lower() - if self.config.relative_prim_path: + if config.relative_prim_path: # If prim path is specified, assert that the last element starts with the right prefix to ensure that # the object will be included in the ControllableObjectViewAPI. - assert self.config.relative_prim_path.split("/")[-1].startswith(f"controllable__{class_name}__"), ( + assert config.relative_prim_path.split("/")[-1].startswith(f"controllable__{class_name}__"), ( "If relative_prim_path is specified, the last element of the path must look like " f"'controllable__{class_name}__robotname' where robotname can be an arbitrary " "string containing no double underscores." ) - assert self.config.relative_prim_path.split("/")[-1].count("__") == 2, ( + assert config.relative_prim_path.split("/")[-1].count("__") == 2, ( "If relative_prim_path is specified, the last element of the path must look like " f"'controllable__{class_name}__robotname' where robotname can be an arbitrary " "string containing no double underscores." ) else: # If prim path is not specified, set it to the default path, but prepend controllable. - self.config.relative_prim_path = f"/controllable__{class_name}__{self.config.name}" + config.relative_prim_path = f"/controllable__{class_name}__{config.name}" + + # Store config and initialize other attributes + self._config = config + self._dof_to_joints = None # dict that will map DOF indices to JointPrims + self._last_action = None + self._controllers = None + self.dof_names_ordered = None + self._control_enabled = True # Run super init with config - super().__init__(config=self.config) + super().__init__(config=config) def _initialize(self): # Assert that the prim path matches ControllableObjectViewAPI's expected format diff --git a/omnigibson/objects/dataset_object.py b/omnigibson/objects/dataset_object.py index b91c9011e..47dbe0f90 100644 --- a/omnigibson/objects/dataset_object.py +++ b/omnigibson/objects/dataset_object.py @@ -77,18 +77,14 @@ def __init__(self, config: DatasetObjectConfig): kwargs (dict): Additional keyword arguments that are used for other super() calls from subclasses, allowing for flexible compositions of various object subclasses (e.g.: Robot is USDObject + ControllableObject). """ - # Store variables + # Validate in_rooms if isinstance(config.in_rooms, str): assert "," not in config.in_rooms - self._in_rooms = [config.in_rooms] if isinstance(config.in_rooms, str) else config.in_rooms # Make sure only one of bounding_box and scale are specified if config.bounding_box is not None and config.scale is not None: raise Exception("You cannot define both scale and bounding box size for a DatasetObject") - # Store config - self._config = config - # Infer the correct usd path to use if config.model is None: available_models = get_all_object_category_models(category=config.category) @@ -105,7 +101,8 @@ def __init__(self, config: DatasetObjectConfig): f"currently broken ): This will be fixed in the next release!" ) - self._model = config.model + # Store config + self._config = config usd_path = self.get_usd_path( category=config.category, model=config.model, diff --git a/omnigibson/objects/light_object.py b/omnigibson/objects/light_object.py index 2b9b99640..888e26f93 100644 --- a/omnigibson/objects/light_object.py +++ b/omnigibson/objects/light_object.py @@ -32,10 +32,10 @@ def __init__(self, config: LightObjectConfig): Args: config (LightObjectConfig): Configuration object containing all parameters for this light object """ - # Make sure primitive type is valid + # Make sure light type is valid assert_valid_key(key=config.light_type, valid_keys=self.LIGHT_TYPES, name="light_type") - # Store the config + # Store config self._config = config # Other attributes to be filled in at runtime diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index 9e4bcb836..57a18b75a 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -30,14 +30,16 @@ def __init__(self, config): Args: config (PrimitiveObjectConfig): Configuration object for this primitive object """ - # Initialize other internal variables + # Make sure primitive type is valid + assert_valid_key(key=config.primitive_type, valid_keys=PRIMITIVE_MESH_TYPES, name="primitive mesh type") + + # Initialize other internal variables self._vis_geom = None self._col_geom = None self._extents = th.ones(3) # (x,y,z extents) - # Make sure primitive type is valid - assert_valid_key(key=config.primitive_type, valid_keys=PRIMITIVE_MESH_TYPES, name="primitive mesh type") - self._primitive_type = config.primitive_type + # Store config + self._config = config super().__init__(config=config) diff --git a/omnigibson/objects/usd_object.py b/omnigibson/objects/usd_object.py index c50f1e375..6f80f14de 100644 --- a/omnigibson/objects/usd_object.py +++ b/omnigibson/objects/usd_object.py @@ -20,7 +20,7 @@ def __init__(self, config: USDObjectConfig): config (USDObjectConfig): Configuration object containing all relevant parameters for initializing this USD object. See the USDObjectConfig dataclass for specific parameters. """ - # Store the config + # Store config self._config = config # Initialize super From cdff8439686c9ef0c4c46d6f092d8b8f23d9773b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:06:21 -0800 Subject: [PATCH 46/50] refactor: Update primitive_type access from self._primitive_type to self._config.primitive_type --- omnigibson/objects/primitive_object.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index 57a18b75a..ab5f5aaf8 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -125,7 +125,7 @@ def radius(self): Returns: float: radius for this object """ - assert_valid_key(key=self._primitive_type, valid_keys=VALID_RADIUS_OBJECTS, name="primitive object with radius") + assert_valid_key(key=self._config.primitive_type, valid_keys=VALID_RADIUS_OBJECTS, name="primitive object with radius") return self._extents[0] / 2.0 @radius.setter From a04ae8c95ab0b896e1d50721897103d89d55baff Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:10:12 -0800 Subject: [PATCH 47/50] refactor: Update PrimitiveObject to use structured config pattern --- omnigibson/objects/primitive_object.py | 28 ++++++++++++-------------- 1 file changed, 13 insertions(+), 15 deletions(-) diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index ab5f5aaf8..4258d3e81 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -25,7 +25,7 @@ class PrimitiveObject(StatefulObject): PrimitiveObjects are objects defined by a single geom, e.g: sphere, mesh, cube, etc. """ - def __init__(self, config): + def __init__(self, config: PrimitiveObjectConfig): """ Args: config (PrimitiveObjectConfig): Configuration object for this primitive object @@ -38,9 +38,7 @@ def __init__(self, config): self._col_geom = None self._extents = th.ones(3) # (x,y,z extents) - # Store config - self._config = config - + # Run super init with config super().__init__(config=config) def _load(self): @@ -71,15 +69,15 @@ def _load(self): def _post_load(self): # Possibly set scalings (only if the scale value is not set) - if self.config.scale is not None: + if self._config.scale is not None: log.warning("Custom scale specified for primitive object, so ignoring radius, height, and size arguments!") else: - if self.config.radius is not None: - self.radius = self.config.radius - if self.config.height is not None: - self.height = self.config.height - if self.config.size is not None: - self.size = self.config.size + if self._config.radius is not None: + self.radius = self._config.radius + if self._config.height is not None: + self.height = self._config.height + if self._config.size is not None: + self.size = self._config.size # This step might will perform cloth remeshing if self._prim_type == PrimType.CLOTH. # Therefore, we need to apply size, radius, and height before this to scale the points properly. @@ -108,11 +106,11 @@ def _initialize(self): else: raise ValueError("Prim type must either be PrimType.RIGID or PrimType.CLOTH for loading a primitive object") - visual_geom_prim.color = self.config.rgba[:3] + visual_geom_prim.color = self._config.rgba[:3] visual_geom_prim.opacity = ( - self.config.rgba[3].item() - if isinstance(self.config.rgba[3], th.Tensor) - else self.config.rgba[3] + self._config.rgba[3].item() + if isinstance(self._config.rgba[3], th.Tensor) + else self._config.rgba[3] ) @property From 0119a6bc5d2cbe90da0163880fa5264f30b455b9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen=20=28aider=29?= Date: Thu, 2 Jan 2025 16:10:52 -0800 Subject: [PATCH 48/50] refactor: Add import for PrimitiveObjectConfig in primitive_object.py --- omnigibson/objects/primitive_object.py | 1 + 1 file changed, 1 insertion(+) diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index 4258d3e81..f888e6f3f 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -4,6 +4,7 @@ import omnigibson.lazy as lazy from omnigibson.objects.stateful_object import StatefulObject from omnigibson.utils.constants import PRIMITIVE_MESH_TYPES, PrimType +from omnigibson.configs.base_config import PrimitiveObjectConfig from omnigibson.utils.physx_utils import bind_material from omnigibson.utils.python_utils import assert_valid_key from omnigibson.utils.render_utils import create_pbr_material From 32edd89a0079ea81bc59661db42b70961939ce3a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen?= Date: Thu, 2 Jan 2025 16:12:46 -0800 Subject: [PATCH 49/50] Read primitive type --- omnigibson/objects/primitive_object.py | 57 ++++++++++++++++---------- 1 file changed, 35 insertions(+), 22 deletions(-) diff --git a/omnigibson/objects/primitive_object.py b/omnigibson/objects/primitive_object.py index f888e6f3f..857e103b4 100644 --- a/omnigibson/objects/primitive_object.py +++ b/omnigibson/objects/primitive_object.py @@ -34,7 +34,10 @@ def __init__(self, config: PrimitiveObjectConfig): # Make sure primitive type is valid assert_valid_key(key=config.primitive_type, valid_keys=PRIMITIVE_MESH_TYPES, name="primitive mesh type") - # Initialize other internal variables + # Store config + self._config = config + + # Initialize other internal variables self._vis_geom = None self._col_geom = None self._extents = th.ones(3) # (x,y,z extents) @@ -49,10 +52,10 @@ def _load(self): # Define a nested mesh corresponding to the root link for this prim og.sim.stage.DefinePrim(f"{self.prim_path}/base_link", "Xform") self._vis_geom = create_primitive_mesh( - prim_path=f"{self.prim_path}/base_link/visuals", primitive_type=self._primitive_type + prim_path=f"{self.prim_path}/base_link/visuals", primitive_type=self._config.primitive_type ) self._col_geom = create_primitive_mesh( - prim_path=f"{self.prim_path}/base_link/collisions", primitive_type=self._primitive_type + prim_path=f"{self.prim_path}/base_link/collisions", primitive_type=self._config.primitive_type ) # Add collision API to collision geom @@ -87,9 +90,9 @@ def _post_load(self): # Cloth primitive does not have collision meshes if self._prim_type != PrimType.CLOTH: # Set the collision approximation appropriately - if self._primitive_type == "Sphere": + if self._config.primitive_type == "Sphere": col_approximation = "boundingSphere" - elif self._primitive_type == "Cube": + elif self._config.primitive_type == "Cube": col_approximation = "boundingCube" else: col_approximation = "convexHull" @@ -109,9 +112,7 @@ def _initialize(self): visual_geom_prim.color = self._config.rgba[:3] visual_geom_prim.opacity = ( - self._config.rgba[3].item() - if isinstance(self._config.rgba[3], th.Tensor) - else self._config.rgba[3] + self._config.rgba[3].item() if isinstance(self._config.rgba[3], th.Tensor) else self._config.rgba[3] ) @property @@ -124,7 +125,9 @@ def radius(self): Returns: float: radius for this object """ - assert_valid_key(key=self._config.primitive_type, valid_keys=VALID_RADIUS_OBJECTS, name="primitive object with radius") + assert_valid_key( + key=self._config.primitive_type, valid_keys=VALID_RADIUS_OBJECTS, name="primitive object with radius" + ) return self._extents[0] / 2.0 @radius.setter @@ -137,12 +140,14 @@ def radius(self, radius): Args: radius (float): radius to set """ - assert_valid_key(key=self._primitive_type, valid_keys=VALID_RADIUS_OBJECTS, name="primitive object with radius") + assert_valid_key( + key=self._config.primitive_type, valid_keys=VALID_RADIUS_OBJECTS, name="primitive object with radius" + ) # Update the extents variable original_extent = self._extents.clone() self._extents = ( th.ones(3) * radius * 2.0 - if self._primitive_type == "Sphere" + if self._config.primitive_type == "Sphere" else th.tensor([radius * 2.0, radius * 2.0, self._extents[2]]) ) attr_pairs = [] @@ -164,7 +169,7 @@ def radius(self, radius): scaling_factor = 2.0 * radius / original_extent[0] for attr, vals in attr_pairs: # If this is a sphere, modify all 3 axes - if self._primitive_type == "Sphere": + if self._config.primitive_type == "Sphere": vals = vals * scaling_factor # Otherwise, just modify the first two dimensions else: @@ -182,7 +187,9 @@ def height(self): Returns: float: height for this object """ - assert_valid_key(key=self._primitive_type, valid_keys=VALID_HEIGHT_OBJECTS, name="primitive object with height") + assert_valid_key( + key=self._config.primitive_type, valid_keys=VALID_HEIGHT_OBJECTS, name="primitive object with height" + ) return self._extents[2] @height.setter @@ -195,7 +202,9 @@ def height(self, height): Args: height (float): height to set """ - assert_valid_key(key=self._primitive_type, valid_keys=VALID_HEIGHT_OBJECTS, name="primitive object with height") + assert_valid_key( + key=self._config.primitive_type, valid_keys=VALID_HEIGHT_OBJECTS, name="primitive object with height" + ) # Update the extents variable original_extent = self._extents.clone() self._extents[2] = height @@ -228,7 +237,9 @@ def size(self): Returns: float: size for this object """ - assert_valid_key(key=self._primitive_type, valid_keys=VALID_SIZE_OBJECTS, name="primitive object with size") + assert_valid_key( + key=self._config.primitive_type, valid_keys=VALID_SIZE_OBJECTS, name="primitive object with size" + ) return self._extents[0] @size.setter @@ -241,7 +252,9 @@ def size(self, size): Args: size (float): size to set """ - assert_valid_key(key=self._primitive_type, valid_keys=VALID_SIZE_OBJECTS, name="primitive object with size") + assert_valid_key( + key=self._config.primitive_type, valid_keys=VALID_SIZE_OBJECTS, name="primitive object with size" + ) # Update the extents variable original_extent = self._extents.clone() @@ -267,19 +280,19 @@ def size(self, size): def _dump_state(self): state = super()._dump_state() # state["extents"] = self._extents - state["radius"] = self.radius if self._primitive_type in VALID_RADIUS_OBJECTS else -1 - state["height"] = self.height if self._primitive_type in VALID_HEIGHT_OBJECTS else -1 - state["size"] = self.size if self._primitive_type in VALID_SIZE_OBJECTS else -1 + state["radius"] = self.radius if self._config.primitive_type in VALID_RADIUS_OBJECTS else -1 + state["height"] = self.height if self._config.primitive_type in VALID_HEIGHT_OBJECTS else -1 + state["size"] = self.size if self._config.primitive_type in VALID_SIZE_OBJECTS else -1 return state def _load_state(self, state): super()._load_state(state=state) # self._extents = th.tensor(state["extents"]) - if self._primitive_type in VALID_RADIUS_OBJECTS: + if self._config.primitive_type in VALID_RADIUS_OBJECTS: self.radius = state["radius"] - if self._primitive_type in VALID_HEIGHT_OBJECTS: + if self._config.primitive_type in VALID_HEIGHT_OBJECTS: self.height = state["height"] - if self._primitive_type in VALID_SIZE_OBJECTS: + if self._config.primitive_type in VALID_SIZE_OBJECTS: self.size = state["size"] def deserialize(self, state): From 80806e3280b9c2969e7d8a5fdfced0ddc33d697d Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 3 Jan 2025 00:14:04 +0000 Subject: [PATCH 50/50] [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci --- omnigibson/configs/base_config.py | 24 +++++++++- omnigibson/configs/env_config.py | 10 +++- omnigibson/configs/object_config.py | 23 +++++---- omnigibson/configs/prim_config.py | 18 ++++++- omnigibson/configs/robot_config.py | 58 ++++++++++++++++++++++- omnigibson/objects/controllable_object.py | 19 ++++---- omnigibson/objects/dataset_object.py | 4 +- omnigibson/objects/light_object.py | 7 +-- omnigibson/objects/stateful_object.py | 2 +- omnigibson/objects/usd_object.py | 2 +- omnigibson/robots/husky.py | 3 +- 11 files changed, 136 insertions(+), 34 deletions(-) diff --git a/omnigibson/configs/base_config.py b/omnigibson/configs/base_config.py index 2e0509e70..90fc7da3a 100644 --- a/omnigibson/configs/base_config.py +++ b/omnigibson/configs/base_config.py @@ -3,20 +3,26 @@ from omegaconf import MISSING from omnigibson.configs.robot_config import ControllerConfig -@dataclass + +@dataclass class BaseConfig: """Base configuration class that all other configs inherit from""" + name: str = MISSING + @dataclass class BasePrimConfig(BaseConfig): """Base configuration for all prims""" + relative_prim_path: Optional[str] = None load_config: Dict[str, Any] = field(default_factory=dict) + @dataclass class EntityConfig(BasePrimConfig): """Configuration for entities""" + scale: Optional[List[float]] = None visible: bool = True visual_only: bool = False @@ -24,54 +30,68 @@ class EntityConfig(BasePrimConfig): self_collisions: bool = False prim_type: str = MISSING + @dataclass class ObjectConfig(EntityConfig): """Configuration for all objects""" + category: str = "object" fixed_base: bool = False abilities: Dict[str, Dict[str, Any]] = field(default_factory=dict) include_default_states: bool = True + @dataclass class StatefulObjectConfig(ObjectConfig): """Configuration for stateful objects""" + abilities: Optional[Dict[str, Dict[str, Any]]] = None include_default_states: bool = True + @dataclass class USDObjectConfig(StatefulObjectConfig): """Configuration for USD-based objects""" + usd_path: str = MISSING encrypted: bool = False + @dataclass class DatasetObjectConfig(StatefulObjectConfig): """Configuration for dataset objects""" + model: Optional[str] = None dataset_type: str = "BEHAVIOR" bounding_box: Optional[List[float]] = None in_rooms: Optional[List[str]] = None xform_props_pre_loaded: bool = True + @dataclass class PrimitiveObjectConfig(StatefulObjectConfig): """Configuration for primitive objects""" + primitive_type: str = MISSING rgba: List[float] = field(default_factory=lambda: [0.5, 0.5, 0.5, 1.0]) radius: Optional[float] = None height: Optional[float] = None size: Optional[float] = None + @dataclass class LightObjectConfig(StatefulObjectConfig): """Configuration for light objects""" + light_type: str = MISSING radius: float = 1.0 intensity: float = 50000.0 -@dataclass + +@dataclass class ControllableObjectConfig(StatefulObjectConfig): """Configuration for controllable objects""" + control_freq: Optional[float] = None action_type: str = "continuous" action_normalize: bool = True diff --git a/omnigibson/configs/env_config.py b/omnigibson/configs/env_config.py index ae33d9abb..2676954be 100644 --- a/omnigibson/configs/env_config.py +++ b/omnigibson/configs/env_config.py @@ -4,23 +4,26 @@ from omnigibson.configs.object_config import ObjectConfig, RobotConfig + @dataclass class RenderConfig: viewer_width: int = 1280 viewer_height: int = 720 -@dataclass + +@dataclass class EnvConfig: action_frequency: int = 60 rendering_frequency: int = 60 physics_frequency: int = 60 device: Optional[str] = None automatic_reset: bool = False - flatten_action_space: bool = False + flatten_action_space: bool = False flatten_obs_space: bool = False initial_pos_z_offset: float = 0.1 external_sensors: Optional[List[Dict[str, Any]]] = None + @dataclass class SceneConfig: type: str = MISSING @@ -33,16 +36,19 @@ class SceneConfig: scene_instance: Optional[str] = None scene_file: Optional[str] = None + @dataclass class TaskConfig: type: str = "DummyTask" params: Dict[str, Any] = field(default_factory=dict) + @dataclass class WrapperConfig: type: Optional[str] = None params: Dict[str, Any] = field(default_factory=dict) + @dataclass class OmniGibsonConfig: env: EnvConfig = field(default_factory=EnvConfig) diff --git a/omnigibson/configs/object_config.py b/omnigibson/configs/object_config.py index fdfc46f54..efe34b070 100644 --- a/omnigibson/configs/object_config.py +++ b/omnigibson/configs/object_config.py @@ -22,7 +22,7 @@ __all__ = [ "ObjectConfig", - "USDObjectConfig", + "USDObjectConfig", "DatasetObjectConfig", "PrimitiveObjectConfig", "LightObjectConfig", @@ -30,9 +30,11 @@ "RobotConfig", ] + @dataclass class RobotConfig(ControllableObjectConfig): """Configuration for robots""" + type: str = MISSING obs_modalities: List[str] = field(default_factory=lambda: ["rgb", "proprio"]) proprio_obs: str = "default" @@ -42,11 +44,14 @@ class RobotConfig(ControllableObjectConfig): disable_grasp_handling: bool = False default_reset_mode: str = "untuck" default_arm_pose: str = "vertical" - controllers: Dict[str, Union[ - ControllerConfig, - JointControllerConfig, - IKControllerConfig, - OSCControllerConfig, - DifferentialDriveConfig, - GripperControllerConfig, - ]] = field(default_factory=dict) + controllers: Dict[ + str, + Union[ + ControllerConfig, + JointControllerConfig, + IKControllerConfig, + OSCControllerConfig, + DifferentialDriveConfig, + GripperControllerConfig, + ], + ] = field(default_factory=dict) diff --git a/omnigibson/configs/prim_config.py b/omnigibson/configs/prim_config.py index 757475ec4..84fcaaf18 100644 --- a/omnigibson/configs/prim_config.py +++ b/omnigibson/configs/prim_config.py @@ -3,50 +3,66 @@ from omegaconf import MISSING from omnigibson.configs.base_config import BasePrimConfig + @dataclass class XFormPrimConfig(BasePrimConfig): """Configuration for XForm prims""" + pass + @dataclass class GeomPrimConfig(XFormPrimConfig): """Configuration for geometry prims""" + pass + @dataclass class CollisionGeomPrimConfig(GeomPrimConfig): """Configuration for collision geometry prims""" + pass + @dataclass class VisualGeomPrimConfig(GeomPrimConfig): """Configuration for visual geometry prims""" + pass + @dataclass class CollisionVisualGeomPrimConfig(CollisionGeomPrimConfig, VisualGeomPrimConfig): """Configuration for combined collision and visual geometry prims""" + pass + @dataclass class RigidPrimConfig(XFormPrimConfig): """Configuration for rigid body prims""" + kinematic_only: Optional[bool] = None belongs_to_articulation: Optional[bool] = None visual_only: Optional[bool] = None mass: Optional[float] = None density: Optional[float] = None + @dataclass class JointPrimConfig(BasePrimConfig): """Configuration for joint prims""" + joint_type: Optional[str] = None - body0: Optional[str] = None + body0: Optional[str] = None body1: Optional[str] = None articulation_view: Optional[Any] = None + @dataclass class EntityPrimConfig(XFormPrimConfig): """Configuration for entity prims""" + visual_only: Optional[bool] = None prim_type: str = MISSING diff --git a/omnigibson/configs/robot_config.py b/omnigibson/configs/robot_config.py index d42ead748..ea5732a4e 100644 --- a/omnigibson/configs/robot_config.py +++ b/omnigibson/configs/robot_config.py @@ -4,9 +4,11 @@ from omnigibson.configs.object_config import ControllableObjectConfig + @dataclass class ControllerConfig: """Base configuration for controllers""" + name: str = MISSING control_freq: Optional[float] = None control_limits: Optional[Dict[str, Any]] = None @@ -15,157 +17,209 @@ class ControllerConfig: use_delta_commands: bool = False use_impedances: bool = False + @dataclass class JointControllerConfig(ControllerConfig): """Configuration for joint controllers""" + motor_type: str = "position" dof_idx: Optional[List[int]] = None pos_kp: Optional[float] = None pos_kd: Optional[float] = None + @dataclass class IKControllerConfig(ControllerConfig): """Configuration for IK controllers""" + task_name: str = MISSING mode: str = "pose_delta_ori" smoothing_filter_size: int = 2 workspace_pose_limiter: Optional[Dict[str, Any]] = None reset_joint_pos: Optional[List[float]] = None + @dataclass class OSCControllerConfig(ControllerConfig): """Configuration for operational space controllers""" + task_name: str = MISSING mode: str = "pose_delta_ori" workspace_pose_limiter: Optional[Dict[str, Any]] = None reset_joint_pos: Optional[List[float]] = None + @dataclass class DifferentialDriveConfig(ControllerConfig): """Configuration for differential drive controllers""" + wheel_radius: float = MISSING wheel_axle_length: float = MISSING + @dataclass class GripperControllerConfig(ControllerConfig): """Configuration for gripper controllers""" + mode: str = "binary" limit_tolerance: float = 0.001 inverted: bool = False -@dataclass + +@dataclass class RobotConfig(ControllableObjectConfig): """Base configuration for robots""" + type: str = MISSING obs_modalities: List[str] = field(default_factory=lambda: ["rgb", "proprio"]) proprio_obs: str = "default" sensor_config: Optional[Dict[str, Any]] = None controllers: Dict[str, ControllerConfig] = field(default_factory=dict) + @dataclass class ManipulationRobotConfig(RobotConfig): """Configuration for manipulation robots""" + grasping_mode: str = "physical" - grasping_direction: str = "lower" + grasping_direction: str = "lower" disable_grasp_handling: bool = False + @dataclass class MobileManipulationRobotConfig(ManipulationRobotConfig): """Configuration for mobile manipulation robots""" + default_reset_mode: str = "untuck" + @dataclass class UntuckedArmPoseRobotConfig(MobileManipulationRobotConfig): """Configuration for robots with untucked arm poses""" + default_arm_pose: str = "vertical" + @dataclass class BehaviorRobotConfig(ManipulationRobotConfig): """Configuration for behavior robots""" + use_ghost_hands: bool = True + @dataclass class FrankaConfig(ManipulationRobotConfig): """Configuration for Franka robots""" + end_effector: str = "gripper" + @dataclass class A1Config(ManipulationRobotConfig): """Configuration for A1 robot""" + end_effector: str = "inspire" + @dataclass class TiagoConfig(UntuckedArmPoseRobotConfig): """Configuration for Tiago robot""" + variant: str = "default" + @dataclass class FetchConfig(UntuckedArmPoseRobotConfig): """Configuration for Fetch robot""" + pass + @dataclass class R1Config(MobileManipulationRobotConfig): """Configuration for R1 robot""" + pass + @dataclass class StretchConfig(ManipulationRobotConfig): """Configuration for Stretch robot""" + pass + @dataclass class VX300SConfig(ManipulationRobotConfig): """Configuration for VX300S robot""" + pass + @dataclass class TwoWheelRobotConfig(RobotConfig): """Configuration for two wheel robots""" + wheel_radius: float = MISSING wheel_axle_length: float = MISSING + @dataclass class HuskyConfig(TwoWheelRobotConfig): """Configuration for Husky robot""" + pass + @dataclass class TurtlebotConfig(TwoWheelRobotConfig): """Configuration for Turtlebot robot""" + pass + @dataclass class FreightConfig(TwoWheelRobotConfig): """Configuration for Freight robot""" + pass + @dataclass class LocobotConfig(TwoWheelRobotConfig): """Configuration for Locobot robot""" + pass + @dataclass class ManipulationRobotConfig(RobotConfig): """Configuration for manipulation robots""" + n_arms: int = 1 arm_names: List[str] = field(default_factory=lambda: ["default"]) finger_lengths: Dict[str, float] = field(default_factory=dict) assisted_grasp_points: Dict[str, Dict[str, List[float]]] = field(default_factory=dict) + @dataclass class LocomotionRobotConfig(RobotConfig): """Configuration for locomotion robots""" + base_joint_names: List[str] = field(default_factory=list) base_control_idx: List[int] = field(default_factory=list) + @dataclass class TwoWheelRobotConfig(LocomotionRobotConfig): """Configuration for two wheel robots""" + wheel_radius: float = MISSING wheel_axle_length: float = MISSING + @dataclass class HolonomicBaseRobotConfig(LocomotionRobotConfig): """Configuration for holonomic base robots""" + base_footprint_link_name: str = MISSING diff --git a/omnigibson/objects/controllable_object.py b/omnigibson/objects/controllable_object.py index f679fece2..2d89da8d4 100644 --- a/omnigibson/objects/controllable_object.py +++ b/omnigibson/objects/controllable_object.py @@ -170,28 +170,28 @@ def _load_controllers(self): # Initialize controllers to create self._controllers = dict() - + # Process controller configs from structured config for name in self._raw_controller_order: # Make sure we have the valid controller name specified assert_valid_key(key=name, valid_keys=self.config.controllers, name="controller name") - + # Get controller config and override input limits if using normalized actions controller_cfg = self.config.controllers[name] if self.config.action_normalize: controller_cfg.command_input_limits = "default" # default is normalized (-1, 1) - + # Create the controller from structured config controller = create_controller(name=controller_cfg.name, **cb.from_torch_recursive(controller_cfg)) - + # Verify the controller's DOFs can all be driven for idx in controller.dof_idx: assert self._joints[ self.dof_names_ordered[idx] ].driven, "Controllers should only control driveable joints!" - + self._controllers[name] = controller - + self.update_controller_mode() def update_controller_mode(self): @@ -245,15 +245,15 @@ def _generate_controller_config(self, custom_config=None): """ # Start with default controller configs controller_config = {} - + # For each controller group for group in self._raw_controller_order: # Get default controller type for this group default_controller = self._default_controllers[group] - + # Get default config for this controller type default_config = self._default_controller_config[group][default_controller] - + # Override with custom config if specified if custom_config is not None and group in custom_config: controller_config[group] = custom_config[group] @@ -273,6 +273,7 @@ def reload_controllers(self, controller_configs=None): if controller_configs is not None: # Create new structured configs from the input from omnigibson.configs.robot_config import ControllerConfig + new_controllers = {} for name, cfg in controller_configs.items(): if isinstance(cfg, dict): diff --git a/omnigibson/objects/dataset_object.py b/omnigibson/objects/dataset_object.py index 47dbe0f90..e1c5681da 100644 --- a/omnigibson/objects/dataset_object.py +++ b/omnigibson/objects/dataset_object.py @@ -215,9 +215,7 @@ def _post_load(self): if self._config.bounding_box is not None: scale = th.ones(3) valid_idxes = self.native_bbox > 1e-4 - scale[valid_idxes] = ( - th.tensor(self._config.bounding_box)[valid_idxes] / self.native_bbox[valid_idxes] - ) + scale[valid_idxes] = th.tensor(self._config.bounding_box)[valid_idxes] / self.native_bbox[valid_idxes] else: scale = th.ones(3) if self._config.scale is None else self._config.scale diff --git a/omnigibson/objects/light_object.py b/omnigibson/objects/light_object.py index 888e26f93..ce1ceddc0 100644 --- a/omnigibson/objects/light_object.py +++ b/omnigibson/objects/light_object.py @@ -34,10 +34,10 @@ def __init__(self, config: LightObjectConfig): """ # Make sure light type is valid assert_valid_key(key=config.light_type, valid_keys=self.LIGHT_TYPES, name="light_type") - + # Store config self._config = config - + # Other attributes to be filled in at runtime self._light_link = None @@ -73,7 +73,7 @@ def _post_load(self): # Set the intensity and radius from config self.intensity = self._config.intensity - + # Only set radius for applicable light types if self._config.light_type in {"Cylinder", "Disk", "Sphere"}: self.radius = self._config.radius @@ -178,6 +178,7 @@ def texture_file_path(self, texture_file_path): texture_file_path (str): path of texture file that should be used for this light """ self._light_link.set_attribute("inputs:texture:file", lazy.pxr.Sdf.AssetPath(texture_file_path)) + @property def light_type(self): """ diff --git a/omnigibson/objects/stateful_object.py b/omnigibson/objects/stateful_object.py index e1bb5a8da..9f1ffce5e 100644 --- a/omnigibson/objects/stateful_object.py +++ b/omnigibson/objects/stateful_object.py @@ -148,7 +148,7 @@ def config(self) -> StatefulObjectConfig: """ return self._config - @property + @property def abilities(self): """ Returns: diff --git a/omnigibson/objects/usd_object.py b/omnigibson/objects/usd_object.py index 6f80f14de..68c3d6665 100644 --- a/omnigibson/objects/usd_object.py +++ b/omnigibson/objects/usd_object.py @@ -22,7 +22,7 @@ def __init__(self, config: USDObjectConfig): """ # Store config self._config = config - + # Initialize super super().__init__(config=config) diff --git a/omnigibson/robots/husky.py b/omnigibson/robots/husky.py index 354e45856..31b620f49 100644 --- a/omnigibson/robots/husky.py +++ b/omnigibson/robots/husky.py @@ -4,12 +4,13 @@ from omnigibson.robots.locomotion_robot import LocomotionRobot from omnigibson.configs.robot_config import HuskyConfig + class Husky(LocomotionRobot): """ Husky robot Reference: https://clearpathrobotics.com/, http://wiki.ros.org/Robots/Husky """ - + def __init__( self, config: HuskyConfig,