diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index b1d55aac0..d64b5ab6e 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -49,4 +49,22 @@ jobs: - name: Install dependencies run: uv sync --all-extras --all-packages --group dev - name: Test with python ${{ matrix.python-version }} - run: uv run pytest \ No newline at end of file + run: uv run pytest + + pyright: + runs-on: ubuntu-latest + strategy: + matrix: + python-version: ["3.10", "3.11", "3.12"] + steps: + - uses: actions/checkout@v4 + - name: Setup uv + uses: astral-sh/setup-uv@v6 + with: + python-version: ${{ matrix.python-version }} + enable-cache: true + version: "0.8.13" + - name: Install dependencies + run: uv sync --all-extras --all-packages --group dev + - name: Test with python ${{ matrix.python-version }} + run: uv run pyright diff --git a/.gitignore b/.gitignore index 4eeda264b..495cf622f 100644 --- a/.gitignore +++ b/.gitignore @@ -5,7 +5,6 @@ videos/ __pycache__/ MUJOCO_LOG.TXT debug.py -typings/ .vscode/ *.ipynb_checkpoints/ *.ipynb @@ -13,4 +12,4 @@ motions/ *_rerun* *.mp4 artifacts/ -.venv/ \ No newline at end of file +.venv/ diff --git a/Makefile b/Makefile index 159ffc866..c77afdb4f 100644 --- a/Makefile +++ b/Makefile @@ -9,4 +9,5 @@ format: .PHONY: test test: - uv run pytest \ No newline at end of file + uv run pytest + uv run pyright diff --git a/pyproject.toml b/pyproject.toml index ea178851d..5b183b912 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -45,6 +45,10 @@ dependencies = [ "mujoco", "trimesh", "viser", + "wandb", + "moviepy", + "tensordict", + "rsl-rl-lib", ] [dependency-groups] @@ -52,7 +56,7 @@ dev = [ {include-group = "lint"}, {include-group = "test"}, "pre-commit", - "ty", + "pyright>=1.1.386", ] lint = [ "ruff" @@ -68,7 +72,6 @@ rl = [ "moviepy >=1.0.0", "rsl-rl-lib", "tensorboard", - "wandb", ] [[tool.uv.index]] @@ -99,14 +102,13 @@ torch = [{ index = "pytorch-cu128", extra = "cu12" }] indent-width = 2 exclude = [ "src/mjlab/third_party", + "typings", ] [tool.ruff.lint] select = ["E4", "E7", "E9", "F", "I", "B"] -[tool.ty.rules] -unresolved-attribute = "ignore" - -[tool.ty.src] -include = ["src", "tests"] -exclude = ["src/mjlab/third_party"] +[tool.pyright] +pythonVersion = "3.10" +ignore = ["./typings", "./src/mjlab/third_party"] +stubPath = "typings" diff --git a/scripts/tracking/data/compare_npz.py b/scripts/tracking/data/compare_npz.py index 387d3229e..a7a61b187 100644 --- a/scripts/tracking/data/compare_npz.py +++ b/scripts/tracking/data/compare_npz.py @@ -1,7 +1,7 @@ import numpy as np -from mjlab import Robot from mjlab.asset_zoo.robots.unitree_g1.g1_constants import G1_ROBOT_CFG +from mjlab.entities import Robot robot = Robot(G1_ROBOT_CFG) diff --git a/scripts/tracking/data/csv_to_npz.py b/scripts/tracking/data/csv_to_npz.py index 2e32af37f..87c91a23a 100644 --- a/scripts/tracking/data/csv_to_npz.py +++ b/scripts/tracking/data/csv_to_npz.py @@ -1,4 +1,5 @@ from dataclasses import replace +from typing import Any import numpy as np import torch @@ -111,10 +112,12 @@ def _slerp( """Spherical linear interpolation between two quaternions.""" slerped_quats = torch.zeros_like(a) for i in range(a.shape[0]): - slerped_quats[i] = quat_slerp(a[i], b[i], blend[i]) + slerped_quats[i] = quat_slerp(a[i], b[i], float(blend[i])) return slerped_quats - def _compute_frame_blend(self, times: torch.Tensor) -> torch.Tensor: + def _compute_frame_blend( + self, times: torch.Tensor + ) -> tuple[torch.Tensor, torch.Tensor, torch.Tensor]: """Computes the frame blend for the motion.""" phase = times / self.duration index_0 = (phase * (self.input_frames - 1)).floor().long() @@ -206,7 +209,7 @@ def run_sim( robot_joint_indexes = robot.find_joints(joint_names, preserve_order=True)[0] # ------- data logger ------------------------------------------------------- - log = { + log: dict[str, Any] = { "fps": [output_fps], "joint_pos": [], "joint_vel": [], diff --git a/scripts/tracking/rl/play.py b/scripts/tracking/rl/play.py index 2e57d9d06..25617c0a0 100644 --- a/scripts/tracking/rl/play.py +++ b/scripts/tracking/rl/play.py @@ -6,6 +6,7 @@ import tyro import wandb +from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv from mjlab.rl import RslRlOnPolicyRunnerCfg, RslRlVecEnvWrapper from mjlab.tasks.tracking.rl import MotionTrackingOnPolicyRunner from mjlab.tasks.tracking.tracking_env_cfg import TrackingEnvCfg @@ -66,15 +67,16 @@ def main( log_dir = resume_path.parent env = gym.make(task, cfg=env_cfg, render_mode="rgb_array" if video else None) + assert isinstance(env, ManagerBasedRlEnv) if video: - video_kwargs = { - "video_folder": log_dir / "videos" / "play", - "step_trigger": lambda step: step == 0, - "video_length": video_length, - "disable_logger": True, - } print("[INFO] Recording videos during training.") - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = gym.wrappers.RecordVideo( + env, + video_folder=str(log_dir / "videos" / "play"), + step_trigger=lambda step: step == 0, + video_length=video_length, + disable_logger=True, + ) env = RslRlVecEnvWrapper(env, clip_actions=agent_cfg.clip_actions) diff --git a/scripts/tracking/rl/train.py b/scripts/tracking/rl/train.py index 50d5d6ddc..037a82dbf 100644 --- a/scripts/tracking/rl/train.py +++ b/scripts/tracking/rl/train.py @@ -1,13 +1,14 @@ """Script to train RL agent with RSL-RL.""" import os +import pathlib from dataclasses import asdict from datetime import datetime from pathlib import Path -from typing import cast import gymnasium as gym import tyro +import wandb from mjlab.rl import RslRlOnPolicyRunnerCfg, RslRlVecEnvWrapper from mjlab.tasks.tracking.rl import MotionTrackingOnPolicyRunner @@ -34,17 +35,14 @@ def main( ): configure_torch_backends() - env_cfg = cast(TrackingEnvCfg, load_cfg_from_registry(task, "env_cfg_entry_point")) - agent_cfg = cast( - RslRlOnPolicyRunnerCfg, load_cfg_from_registry(task, "rl_cfg_entry_point") - ) + env_cfg = load_cfg_from_registry(task, "env_cfg_entry_point") + agent_cfg = load_cfg_from_registry(task, "rl_cfg_entry_point") + assert isinstance(env_cfg, TrackingEnvCfg) + assert isinstance(agent_cfg, RslRlOnPolicyRunnerCfg) # Check if the registry name includes alias, if not, append ":latest". if ":" not in registry_name: registry_name += ":latest" - import pathlib - - import wandb api = wandb.Api() artifact = api.artifact(registry_name) @@ -73,6 +71,7 @@ def main( env = gym.make(task, cfg=env_cfg) # Save resume path before creating a new log_dir. + resume_path = None if agent_cfg.resume: resume_path = get_checkpoint_path( log_root_path, agent_cfg.load_run, agent_cfg.load_checkpoint diff --git a/scripts/velocity/rl/play.py b/scripts/velocity/rl/play.py index d3a11c965..d84336ae7 100644 --- a/scripts/velocity/rl/play.py +++ b/scripts/velocity/rl/play.py @@ -9,7 +9,9 @@ import tyro from rsl_rl.runners import OnPolicyRunner +from mjlab.envs.manager_based_env_config import ManagerBasedEnvCfg from mjlab.rl import RslRlVecEnvWrapper +from mjlab.rl.config import RslRlOnPolicyRunnerCfg from mjlab.third_party.isaaclab.isaaclab_tasks.utils.parse_cfg import ( load_cfg_from_registry, ) @@ -29,7 +31,7 @@ def main( task: str, - wandb_run_path: str, + wandb_run_path: Path, motion_file: str | None = None, num_envs: int | None = None, device: str | None = None, @@ -41,6 +43,8 @@ def main( ): env_cfg = load_cfg_from_registry(task, "env_cfg_entry_point") agent_cfg = load_cfg_from_registry(task, "rl_cfg_entry_point") + assert isinstance(env_cfg, ManagerBasedEnvCfg) + assert isinstance(agent_cfg, RslRlOnPolicyRunnerCfg) env_cfg.sim.num_envs = num_envs or env_cfg.sim.num_envs env_cfg.sim.device = device or env_cfg.sim.device @@ -71,9 +75,9 @@ def main( env = RslRlVecEnvWrapper(env, clip_actions=agent_cfg.clip_actions) runner = OnPolicyRunner( - env, asdict(agent_cfg), log_dir=log_dir, device=agent_cfg.device + env, asdict(agent_cfg), log_dir=str(log_dir), device=agent_cfg.device ) - runner.load(resume_path, map_location=agent_cfg.device) + runner.load(str(resume_path), map_location=agent_cfg.device) policy = runner.get_inference_policy(device=env.device) diff --git a/scripts/velocity/rl/train.py b/scripts/velocity/rl/train.py index 3286cbcdd..97b9454eb 100644 --- a/scripts/velocity/rl/train.py +++ b/scripts/velocity/rl/train.py @@ -10,7 +10,9 @@ import tyro from rsl_rl.runners import OnPolicyRunner +from mjlab.envs.manager_based_rl_env_config import ManagerBasedRlEnvCfg from mjlab.rl import RslRlVecEnvWrapper +from mjlab.rl.config import RslRlOnPolicyRunnerCfg from mjlab.third_party.isaaclab.isaaclab_tasks.utils.parse_cfg import ( load_cfg_from_registry, ) @@ -37,6 +39,8 @@ def main( ): env_cfg = load_cfg_from_registry(task, "env_cfg_entry_point") agent_cfg = load_cfg_from_registry(task, "rl_cfg_entry_point") + assert isinstance(env_cfg, ManagerBasedRlEnvCfg) + assert isinstance(agent_cfg, RslRlOnPolicyRunnerCfg) env_cfg.sim.num_envs = num_envs or env_cfg.sim.num_envs agent_cfg.max_iterations = max_iterations or agent_cfg.max_iterations @@ -59,10 +63,11 @@ def main( env = gym.make(task, cfg=env_cfg) # Save resume path before creating a new log_dir. - if agent_cfg.resume: - resume_path = get_checkpoint_path( - log_root_path, agent_cfg.load_run, agent_cfg.load_checkpoint - ) + resume_path = ( + get_checkpoint_path(log_root_path, agent_cfg.load_run, agent_cfg.load_checkpoint) + if agent_cfg.resume + else None + ) # Wrap for video recording. if video: @@ -80,14 +85,14 @@ def main( runner = OnPolicyRunner( env, asdict(agent_cfg), - log_dir=log_dir, + log_dir=str(log_dir), device=agent_cfg.device, ) runner.add_git_repo_to_log(__file__) - if agent_cfg.resume: + if resume_path is not None: print(f"[INFO]: Loading model checkpoint from: {resume_path}") - runner.load(resume_path) + runner.load(str(resume_path)) dump_yaml(log_dir / "params" / "env.yaml", asdict(env_cfg)) dump_yaml(log_dir / "params" / "agent.yaml", asdict(agent_cfg)) diff --git a/src/mjlab/entities/robots/robot.py b/src/mjlab/entities/robots/robot.py index 12d5c8fe2..2d2535dff 100644 --- a/src/mjlab/entities/robots/robot.py +++ b/src/mjlab/entities/robots/robot.py @@ -49,7 +49,7 @@ def __init__(self, robot_cfg: RobotCfg): if actuator.trntype != mujoco.mjtTrn.mjTRN_JOINT: continue self.actuator_to_joint[actuator.name] = actuator.target - self.jnt_actuators = list(self.actuator_to_joint.values()) + self.joint_actuators = list(self.actuator_to_joint.values()) # Sensors. self._sensor_names = [s.name for s in self._spec.sensors] @@ -166,7 +166,7 @@ def initialize( ) local_act_ids = resolve_matching_names( - self._actuator_names, self.jnt_actuators, True + self._actuator_names, self.joint_actuators, True )[0] self._actuator_ids_global = torch.tensor( [indexing.actuator_local2global[lid] for lid in local_act_ids], diff --git a/src/mjlab/envs/manager_based_env.py b/src/mjlab/envs/manager_based_env.py index 96b6ec2b8..51b220c09 100644 --- a/src/mjlab/envs/manager_based_env.py +++ b/src/mjlab/envs/manager_based_env.py @@ -93,7 +93,7 @@ def reset( self, *, seed: int | None = None, - env_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | None = None, options: dict[str, Any] | None = None, ) -> tuple[types.VecEnvObs, dict]: del options # Unused. @@ -140,7 +140,7 @@ def update_visualizers(self, scn) -> None: # Private methods. - def _reset_idx(self, env_ids: torch.Tensor | slice | None = None) -> None: + def _reset_idx(self, env_ids: torch.Tensor | None = None) -> None: self.scene.reset(env_ids) if "reset" in self.event_manager.available_modes: env_step_count = self._sim_step_counter // self.cfg.decimation diff --git a/src/mjlab/envs/manager_based_rl_env.py b/src/mjlab/envs/manager_based_rl_env.py index 0700e5765..38e5c8d32 100644 --- a/src/mjlab/envs/manager_based_rl_env.py +++ b/src/mjlab/envs/manager_based_rl_env.py @@ -72,7 +72,7 @@ def load_managers(self) -> None: if "startup" in self.event_manager.available_modes: self.event_manager.apply(mode="startup") - def step(self, action: torch.Tensor) -> types.VecEnvStepReturn: + def step(self, action: torch.Tensor) -> types.VecEnvStepReturn: # pyright: ignore[reportIncompatibleMethodOverride] self.action_manager.process_action(action.to(self.device)) for _ in range(self.cfg.decimation): @@ -138,10 +138,12 @@ def _configure_gym_env_spaces(self) -> None: has_concatenated_obs = self.observation_manager.group_obs_concatenate[group_name] group_dim = self.observation_manager.group_obs_dim[group_name] if has_concatenated_obs: + assert isinstance(group_dim, tuple) self.single_observation_space[group_name] = gym.spaces.Box( low=-math.inf, high=math.inf, shape=group_dim ) else: + assert not isinstance(group_dim, tuple) group_term_cfgs = self.observation_manager._group_obs_term_cfgs[group_name] for term_name, term_dim, _term_cfg in zip( group_term_names, group_dim, group_term_cfgs, strict=False @@ -162,7 +164,7 @@ def _configure_gym_env_spaces(self) -> None: self.single_action_space, self.num_envs ) - def _reset_idx(self, env_ids: torch.Tensor | slice | None = None) -> None: + def _reset_idx(self, env_ids: torch.Tensor | None = None) -> None: self.curriculum_manager.compute(env_ids=env_ids) # Reset the internal buffers of the scene elements. self.scene.reset(env_ids) diff --git a/src/mjlab/envs/mdp/actions/joint_actions.py b/src/mjlab/envs/mdp/actions/joint_actions.py index 1d167c1fc..8f66b359e 100644 --- a/src/mjlab/envs/mdp/actions/joint_actions.py +++ b/src/mjlab/envs/mdp/actions/joint_actions.py @@ -1,6 +1,6 @@ from __future__ import annotations -from typing import TYPE_CHECKING, Sequence +from typing import TYPE_CHECKING import torch @@ -18,15 +18,14 @@ class JointAction(ActionTerm): """Base class for joint actions.""" - cfg: actions_config.JointActionCfg _asset: Robot def __init__(self, cfg: actions_config.JointActionCfg, env: ManagerBasedEnv): super().__init__(cfg=cfg, env=env) self._actuator_ids, self._actuator_names = self._asset.find_actuators( - self.cfg.actuator_names, - preserve_order=self.cfg.preserve_order, + cfg.actuator_names, + preserve_order=cfg.preserve_order, ) self._num_joints = len(self._actuator_ids) self._action_dim = len(self._actuator_ids) @@ -39,7 +38,7 @@ def __init__(self, cfg: actions_config.JointActionCfg, env: ManagerBasedEnv): elif isinstance(cfg.scale, dict): self._scale = torch.ones(self.num_envs, self.action_dim, device=self.device) index_list, _, value_list = resolve_matching_names_values( - self.cfg.scale, self._actuator_names + cfg.scale, self._actuator_names ) self._scale[:, index_list] = torch.tensor(value_list, device=self.device) else: @@ -52,7 +51,7 @@ def __init__(self, cfg: actions_config.JointActionCfg, env: ManagerBasedEnv): elif isinstance(cfg.offset, dict): self._offset = torch.zeros_like(self._raw_actions) index_list, _, value_list = resolve_matching_names_values( - self.cfg.offset, self._actuator_names + cfg.offset, self._actuator_names ) self._offset[:, index_list] = torch.tensor(value_list, device=self.device) else: @@ -82,7 +81,7 @@ def process_actions(self, actions: torch.Tensor): self._raw_actions[:] = actions self._processed_actions = self._raw_actions * self._scale + self._offset - def reset(self, env_ids: Sequence[int] | None = None) -> None: + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: self._raw_actions[env_ids] = 0.0 diff --git a/src/mjlab/envs/mdp/events.py b/src/mjlab/envs/mdp/events.py index 1919ff295..d016c1409 100644 --- a/src/mjlab/envs/mdp/events.py +++ b/src/mjlab/envs/mdp/events.py @@ -108,11 +108,15 @@ def reset_joints_by_scale( joint_pos_limits = soft_joint_pos_limits[env_ids][:, asset_cfg.joint_ids] joint_pos = joint_pos.clamp_(joint_pos_limits[..., 0], joint_pos_limits[..., 1]) + joint_ids = asset_cfg.joint_ids + if isinstance(joint_ids, list): + joint_ids = torch.tensor(joint_ids, device=env.device) + asset.write_joint_state_to_sim( joint_pos.view(len(env_ids), -1), joint_vel.view(len(env_ids), -1), env_ids=env_ids, - joint_ids=asset_cfg.joint_ids, + joint_ids=joint_ids, ) @@ -457,6 +461,11 @@ def randomize_actuator_gains( dtype=torch.int, device=env.device, ) + local_act_ids = torch.tensor( + local_act_ids, + dtype=torch.int, + device=env.device, + ) env_grid, act_grid = torch.meshgrid(env_ids, act_ids, indexing="ij") diff --git a/src/mjlab/managers/action_manager.py b/src/mjlab/managers/action_manager.py index f2424a8b9..490a1933c 100644 --- a/src/mjlab/managers/action_manager.py +++ b/src/mjlab/managers/action_manager.py @@ -17,10 +17,9 @@ class ActionTerm(ManagerTermBase): """Base class for action terms.""" - cfg: ActionTermCfg - def __init__(self, cfg: ActionTermCfg, env: ManagerBasedEnv): - super().__init__(cfg, env) + self.cfg = cfg + super().__init__(env) self._asset = self._env.scene[self.cfg.asset_name] @property @@ -44,7 +43,8 @@ def raw_action(self) -> torch.Tensor: class ActionManager(ManagerBase): def __init__(self, cfg: object, env: ManagerBasedEnv): - super().__init__(cfg=cfg, env=env) + self.cfg = cfg + super().__init__(env=env) # Create buffers to store actions. self._action = torch.zeros( diff --git a/src/mjlab/managers/command_manager.py b/src/mjlab/managers/command_manager.py index 932338b8b..e1346074c 100644 --- a/src/mjlab/managers/command_manager.py +++ b/src/mjlab/managers/command_manager.py @@ -17,11 +17,9 @@ class CommandTerm(ManagerTermBase): """Base class for command terms.""" - cfg: CommandTermCfg - def __init__(self, cfg: CommandTermCfg, env: ManagerBasedRlEnv): - super().__init__(cfg, env) - + self.cfg = cfg + super().__init__(env) self.metrics = dict() self.time_left = torch.zeros(self.num_envs, device=self.device) self.command_counter = torch.zeros( @@ -40,7 +38,8 @@ def _debug_vis_impl(self, scn): def command(self): raise NotImplementedError - def reset(self, env_ids: torch.Tensor) -> dict[str, float]: + def reset(self, env_ids: torch.Tensor | slice | None) -> dict[str, float]: + assert isinstance(env_ids, torch.Tensor) extras = {} for metric_name, metric_value in self.metrics.items(): extras[metric_name] = torch.mean(metric_value[env_ids]).item() @@ -66,17 +65,17 @@ def _resample(self, env_ids: torch.Tensor) -> None: self.command_counter[env_ids] += 1 @abc.abstractmethod - def _update_metrics(self): + def _update_metrics(self) -> None: """Update the metrics based on the current state.""" raise NotImplementedError @abc.abstractmethod - def _resample_command(self, env_ids: torch.Tensor): + def _resample_command(self, env_ids: torch.Tensor) -> None: """Resample the command for the specified environments.""" raise NotImplementedError @abc.abstractmethod - def _update_command(self): + def _update_command(self) -> None: """Update the command based on the current state.""" raise NotImplementedError @@ -87,8 +86,8 @@ class CommandManager(ManagerBase): def __init__(self, cfg: object, env: ManagerBasedRlEnv): self._terms: dict[str, CommandTerm] = dict() - super().__init__(cfg, env) - + self.cfg = cfg + super().__init__(env) self._commands = dict() def __str__(self) -> str: @@ -123,7 +122,7 @@ def get_active_iterable_terms( idx += term.command.shape[1] return terms - def reset(self, env_ids: torch.Tensor) -> dict[str, torch.Tensor]: + def reset(self, env_ids: torch.Tensor | None) -> dict[str, torch.Tensor]: extras = {} for name, term in self._terms.items(): metrics = term.reset(env_ids=env_ids) diff --git a/src/mjlab/managers/curriculum_manager.py b/src/mjlab/managers/curriculum_manager.py index 68c2ed9e0..804cf83e0 100644 --- a/src/mjlab/managers/curriculum_manager.py +++ b/src/mjlab/managers/curriculum_manager.py @@ -21,7 +21,8 @@ def __init__(self, cfg: object, env: ManagerBasedRlEnv): self._term_cfgs: list[CurriculumTermCfg] = list() self._class_term_cfgs: list[CurriculumTermCfg] = list() - super().__init__(cfg, env) + self.cfg = cfg + super().__init__(env) self._curriculum_state = dict() for term_name in self._term_names: diff --git a/src/mjlab/managers/event_manager.py b/src/mjlab/managers/event_manager.py index da259fde0..578c9fdfa 100644 --- a/src/mjlab/managers/event_manager.py +++ b/src/mjlab/managers/event_manager.py @@ -17,12 +17,13 @@ class EventManager(ManagerBase): _env: ManagerBasedEnv def __init__(self, cfg: object, env: ManagerBasedEnv): + self.cfg = cfg self._mode_term_names: dict[EventMode, list[str]] = dict() self._mode_term_cfgs: dict[EventMode, list[EventTermCfg]] = dict() self._mode_class_term_cfgs: dict[EventMode, list[EventTermCfg]] = dict() self._domain_randomization_fields: list[str] = list() - super().__init__(cfg=cfg, env=env) + super().__init__(env=env) def __str__(self) -> str: msg = f" contains {len(self._mode_term_names)} active terms.\n" @@ -70,7 +71,7 @@ def domain_randomization_fields(self) -> list[str]: # Methods. - def reset(self, env_ids: torch.Tensor | slice | None = None): + def reset(self, env_ids: torch.Tensor | None = None): for mode_cfg in self._mode_class_term_cfgs.values(): for term_cfg in mode_cfg: term_cfg.func.reset(env_ids=env_ids) @@ -81,6 +82,7 @@ def reset(self, env_ids: torch.Tensor | slice | None = None): if "interval" in self._mode_term_cfgs: for index, term_cfg in enumerate(self._mode_class_term_cfgs["interval"]): if not term_cfg.is_global_time: + assert term_cfg.interval_range_s is not None lower, upper = term_cfg.interval_range_s sampled_interval = ( torch.rand(num_envs, device=self.device) * (upper - lower) + lower @@ -112,9 +114,11 @@ def apply( for index, term_cfg in enumerate(self._mode_term_cfgs[mode]): if mode == "interval": time_left = self._interval_term_time_left[index] + assert dt is not None time_left -= dt if term_cfg.is_global_time: if time_left < 1e-6: + assert term_cfg.interval_range_s is not None lower, upper = term_cfg.interval_range_s sampled_interval = torch.rand(1) * (upper - lower) + lower self._interval_term_time_left[index][:] = sampled_interval @@ -122,6 +126,7 @@ def apply( else: valid_env_ids = (time_left < 1e-6).nonzero().flatten() if len(valid_env_ids) > 0: + assert term_cfg.interval_range_s is not None lower, upper = term_cfg.interval_range_s sampled_time = ( torch.rand(len(valid_env_ids), device=self.device) * (upper - lower) @@ -130,6 +135,7 @@ def apply( self._interval_term_time_left[index][valid_env_ids] = sampled_time term_cfg.func(self._env, valid_env_ids, **term_cfg.params) elif mode == "reset": + assert global_env_step_count is not None min_step_count = term_cfg.min_step_count_between_reset if env_ids is None: env_ids = slice(None) @@ -145,10 +151,10 @@ def apply( steps_since_triggered = global_env_step_count - last_triggered_step valid_trigger = steps_since_triggered >= min_step_count valid_trigger |= (last_triggered_step == 0) & ~triggered_at_least_once - if env_ids == slice(None): - valid_env_ids = valid_trigger.nonzero().flatten() - else: + if isinstance(env_ids, torch.Tensor): valid_env_ids = env_ids[valid_trigger] + else: + valid_env_ids = valid_trigger.nonzero().flatten() if len(valid_env_ids) > 0: self._reset_term_last_triggered_once[index][valid_env_ids] = True self._reset_term_last_triggered_step_id[index][valid_env_ids] = ( diff --git a/src/mjlab/managers/manager_base.py b/src/mjlab/managers/manager_base.py index 959b5081e..21ba961e3 100644 --- a/src/mjlab/managers/manager_base.py +++ b/src/mjlab/managers/manager_base.py @@ -14,8 +14,7 @@ class ManagerTermBase: - def __init__(self, cfg: ManagerTermBaseCfg, env: ManagerBasedEnv): - self.cfg = cfg + def __init__(self, env: ManagerBasedEnv): self._env = env # Properties. @@ -34,7 +33,7 @@ def name(self) -> str: # Methods. - def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + def reset(self, env_ids: torch.Tensor | slice | None) -> Any: """Resets the manager term.""" del env_ids # Unused. pass @@ -47,8 +46,7 @@ def __call__(self, *args) -> Any: class ManagerBase(abc.ABC): """Base class for all managers.""" - def __init__(self, cfg, env: ManagerBasedEnv): - self.cfg = cfg + def __init__(self, env: ManagerBasedEnv): self._env = env self._prepare_terms() @@ -70,7 +68,7 @@ def active_terms(self) -> list[str] | dict[Any, list[str]]: # Methods. - def reset(self, env_ids: torch.Tensor | slice | None = None) -> dict[str, float]: + def reset(self, env_ids: torch.Tensor) -> dict[str, Any]: """Resets the manager and returns logging info for the current step.""" del env_ids # Unused. return {} diff --git a/src/mjlab/managers/manager_term_config.py b/src/mjlab/managers/manager_term_config.py index 468596661..87a6bef59 100644 --- a/src/mjlab/managers/manager_term_config.py +++ b/src/mjlab/managers/manager_term_config.py @@ -3,7 +3,7 @@ from dataclasses import dataclass, field from typing import TYPE_CHECKING, Any, Callable, Literal, ParamSpec, TypeVar -import torch +from mjlab.utils.noise.noise_cfg import NoiseCfg, NoiseModelCfg if TYPE_CHECKING: from mjlab.managers.action_manager import ActionTerm @@ -19,7 +19,7 @@ def term(term_cls: Callable[P, T], *args: P.args, **kwargs: P.kwargs) -> T: @dataclass class ManagerTermBaseCfg: - func: Callable + func: Any params: dict[str, Any] = field(default_factory=lambda: {}) @@ -88,7 +88,7 @@ class EventTermCfg(ManagerTermBaseCfg): class ObservationTermCfg(ManagerTermBaseCfg): """Configuration for an observation term.""" - noise: Any | None = None + noise: NoiseCfg | NoiseModelCfg | None = None clip: tuple[float, float] | None = None @@ -110,7 +110,7 @@ class ObservationGroupCfg: class RewardTermCfg(ManagerTermBaseCfg): """Configuration for a reward term.""" - func: Callable[..., torch.Tensor] + func: Any weight: float # TODO(kevin): Sanity check weight is valid type. diff --git a/src/mjlab/managers/observation_manager.py b/src/mjlab/managers/observation_manager.py index 446833042..c25f4d230 100644 --- a/src/mjlab/managers/observation_manager.py +++ b/src/mjlab/managers/observation_manager.py @@ -12,11 +12,14 @@ class ObservationManager(ManagerBase): def __init__(self, cfg: object, env): - super().__init__(cfg=cfg, env=env) + self.cfg = cfg + super().__init__(env=env) self._group_obs_dim: dict[str, tuple[int, ...] | list[tuple[int, ...]]] = dict() + for group_name, group_term_dims in self._group_obs_term_dim.items(): if self._group_obs_concatenate[group_name]: + # All observation terms will be concatenated. try: term_dims = torch.stack( [torch.tensor(dims, device="cpu") for dims in group_term_dims], dim=0 @@ -37,6 +40,8 @@ def __init__(self, cfg: object, env): f"Unable to concatenate observation terms in group {group_name}." ) from None else: + # Observation terms will be returned as a dictionary; we will store a + # list of their dimensions. self._group_obs_dim[group_name] = group_term_dims self._obs_buffer: dict[str, torch.Tensor | dict[str, torch.Tensor]] | None = None @@ -69,16 +74,20 @@ def get_active_iterable_terms( if self._obs_buffer is None: self.compute() + assert self._obs_buffer is not None obs_buffer: dict[str, torch.Tensor | dict[str, torch.Tensor]] = self._obs_buffer for group_name, _ in self.group_obs_dim.items(): if not self.group_obs_concatenate[group_name]: - for name, term in obs_buffer[group_name].items(): + buffers = obs_buffer[group_name] + assert isinstance(buffers, dict) + for name, term in buffers.items(): terms.append((group_name + "-" + name, term[env_idx].cpu().tolist())) continue idx = 0 data = obs_buffer[group_name] + assert isinstance(data, torch.Tensor) for name, shape in zip( self._group_obs_term_names[group_name], self._group_obs_term_dim[group_name], @@ -94,7 +103,7 @@ def get_active_iterable_terms( # Properties. @property - def active_terms(self) -> list[str] | dict[str, list[str]]: + def active_terms(self) -> dict[str, list[str]]: return self._group_obs_term_names @property @@ -116,12 +125,12 @@ def reset(self, env_ids: torch.Tensor | slice | None = None) -> dict[str, float] for term_cfg in group_cfg: term_cfg.func.reset(env_ids=env_ids) # TODO: History. - for mod in self._group_obs_class_instances: + for mod in self._group_obs_class_instances.values(): mod.reset(env_ids=env_ids) return {} def compute(self) -> dict[str, torch.Tensor | dict[str, torch.Tensor]]: - obs_buffer = dict() + obs_buffer: dict[str, torch.Tensor | dict[str, torch.Tensor]] = dict() for group_name in self._group_obs_term_names: obs_buffer[group_name] = self.compute_group(group_name) self._obs_buffer = obs_buffer @@ -129,19 +138,16 @@ def compute(self) -> dict[str, torch.Tensor | dict[str, torch.Tensor]]: def compute_group(self, group_name: str) -> torch.Tensor | dict[str, torch.Tensor]: group_term_names = self._group_obs_term_names[group_name] - group_obs = dict.fromkeys(group_term_names, None) + group_obs: dict[str, torch.Tensor] = {} obs_terms = zip( group_term_names, self._group_obs_term_cfgs[group_name], strict=False ) for term_name, term_cfg in obs_terms: obs: torch.Tensor = term_cfg.func(self._env, **term_cfg.params).clone() if isinstance(term_cfg.noise, noise_cfg.NoiseCfg): - obs = term_cfg.noise.func(obs, term_cfg.noise) - elif ( - isinstance(term_cfg.noise, noise_cfg.NoiseModelCfg) - and term_cfg.noise.func is not None - ): - obs = term_cfg.noise.func(obs) + obs = term_cfg.noise.apply(obs) + elif isinstance(term_cfg.noise, noise_cfg.NoiseModelCfg): + obs = self._group_obs_class_instances[term_name](obs) group_obs[term_name] = obs if self._group_obs_concatenate[group_name]: return torch.cat( @@ -156,7 +162,7 @@ def _prepare_terms(self) -> None: self._group_obs_class_term_cfgs: dict[str, list[ObservationTermCfg]] = dict() self._group_obs_concatenate: dict[str, bool] = dict() self._group_obs_concatenate_dim: dict[str, int] = dict() - self._group_obs_class_instances: list[noise_model.NoiseModel] = list() + self._group_obs_class_instances: dict[str, noise_model.NoiseModel] = {} group_cfg_items = get_terms(self.cfg, ObservationGroupCfg).items() for group_name, group_cfg in group_cfg_items: @@ -198,13 +204,11 @@ def _prepare_terms(self) -> None: term_cfg.noise, noise_cfg.NoiseModelCfg ): noise_model_cls = term_cfg.noise.class_type - if not issubclass(noise_model_cls, noise_model.NoiseModel): - raise TypeError( - f"Class type for observation term '{term_name}' NoiseModelCfg" - f" is not a subclass of 'NoiseModel'. Received: '{type(noise_model_cls)}'." - ) - # Initialize func to be the noise model class instance. - term_cfg.noise.func = noise_model_cls( + assert issubclass(noise_model_cls, noise_model.NoiseModel), ( + f"Class type for observation term '{term_name}' NoiseModelCfg" + f" is not a subclass of 'NoiseModel'. Received: '{type(noise_model_cls)}'." + ) + # Create and store noise model instance. + self._group_obs_class_instances[term_name] = noise_model_cls( term_cfg.noise, num_envs=self._env.num_envs, device=self._env.device ) - self._group_obs_class_instances.append(term_cfg.noise.func) diff --git a/src/mjlab/managers/reward_manager.py b/src/mjlab/managers/reward_manager.py index f28c51994..5f3a50628 100644 --- a/src/mjlab/managers/reward_manager.py +++ b/src/mjlab/managers/reward_manager.py @@ -21,8 +21,8 @@ def __init__(self, cfg: object, env: ManagerBasedRlEnv): self._term_cfgs: list[RewardTermCfg] = list() self._class_term_cfgs: list[RewardTermCfg] = list() - super().__init__(cfg=cfg, env=env) - + self.cfg = cfg + super().__init__(env=env) self._episode_sums = dict() for term_name in self._term_names: self._episode_sums[term_name] = torch.zeros( diff --git a/src/mjlab/managers/scene_entity_config.py b/src/mjlab/managers/scene_entity_config.py index be0a77160..11a7fd2b6 100644 --- a/src/mjlab/managers/scene_entity_config.py +++ b/src/mjlab/managers/scene_entity_config.py @@ -31,11 +31,11 @@ def resolve(self, scene: Scene) -> None: self._resolve_site_names(scene) def _resolve_joint_names(self, scene: Scene) -> None: - if self.joint_names is not None or self.joint_ids != slice(None): + if self.joint_names is not None or isinstance(self.joint_ids, list): entity: Robot = scene[self.name] # Joint name regex --> joint indices. - if self.joint_names is not None and self.joint_ids != slice(None): + if self.joint_names is not None and isinstance(self.joint_ids, list): if isinstance(self.joint_names, str): self.joint_names = [self.joint_names] if isinstance(self.joint_ids, int): @@ -62,17 +62,17 @@ def _resolve_joint_names(self, scene: Scene) -> None: self.joint_ids = slice(None) # Joint indices --> joint names. - elif self.joint_ids != slice(None): + elif isinstance(self.joint_ids, list): if isinstance(self.joint_ids, int): self.joint_ids = [self.joint_ids] self.joint_names = [entity.joint_names[i] for i in self.joint_ids] def _resolve_body_names(self, scene: Scene) -> None: - if self.body_names is not None or self.body_ids != slice(None): + if self.body_names is not None or isinstance(self.body_ids, list): entity: Robot = scene[self.name] # Body name regex --> body indices. - if self.body_names is not None and self.body_ids != slice(None): + if self.body_names is not None and isinstance(self.body_ids, list): if isinstance(self.body_names, str): self.body_names = [self.body_names] if isinstance(self.body_ids, int): @@ -98,17 +98,17 @@ def _resolve_body_names(self, scene: Scene) -> None: self.body_ids = slice(None) # Body indices --> body names. - elif self.body_ids != slice(None): + elif isinstance(self.body_ids, list): if isinstance(self.body_ids, int): self.body_ids = [self.body_ids] self.body_names = [entity.body_names[i] for i in self.body_ids] def _resolve_geom_names(self, scene: Scene) -> None: - if self.geom_names is not None or self.geom_ids != slice(None): + if self.geom_names is not None or isinstance(self.geom_ids, list): entity: Robot = scene[self.name] # Geom name regex --> geom indices. - if self.geom_names is not None and self.geom_ids != slice(None): + if self.geom_names is not None and isinstance(self.geom_ids, list): if isinstance(self.geom_names, str): self.geom_names = [self.geom_names] if isinstance(self.geom_ids, int): @@ -134,17 +134,17 @@ def _resolve_geom_names(self, scene: Scene) -> None: self.geom_ids = slice(None) # Geom indices --> geom names. - elif self.geom_ids != slice(None): + elif isinstance(self.geom_ids, list): if isinstance(self.geom_ids, int): self.geom_ids = [self.geom_ids] self.geom_names = [entity.geom_names[i] for i in self.geom_ids] def _resolve_site_names(self, scene: Scene) -> None: - if self.site_names is not None or self.site_ids != slice(None): + if self.site_names is not None or isinstance(self.site_ids, list): entity: Robot = scene[self.name] # Site name regex --> site indices. - if self.site_names is not None and self.site_ids != slice(None): + if self.site_names is not None and isinstance(self.site_ids, list): if isinstance(self.site_names, str): self.site_names = [self.site_names] if isinstance(self.site_ids, int): @@ -170,7 +170,7 @@ def _resolve_site_names(self, scene: Scene) -> None: self.site_ids = slice(None) # Site indices --> site names. - elif self.site_ids != slice(None): + elif isinstance(self.site_ids, list): if isinstance(self.site_ids, int): self.site_ids = [self.site_ids] self.site_names = [entity.site_names[i] for i in self.site_ids] diff --git a/src/mjlab/managers/termination_manager.py b/src/mjlab/managers/termination_manager.py index a8f8948f6..c1bec2bd7 100644 --- a/src/mjlab/managers/termination_manager.py +++ b/src/mjlab/managers/termination_manager.py @@ -21,7 +21,8 @@ def __init__(self, cfg: object, env: ManagerBasedRlEnv): self._term_cfgs: list[TerminationTermCfg] = list() self._class_term_cfgs: list[TerminationTermCfg] = list() - super().__init__(cfg, env) + self.cfg = cfg + super().__init__(env) self._term_dones = dict() for term_name in self._term_names: diff --git a/src/mjlab/rl/vecenv_wrapper.py b/src/mjlab/rl/vecenv_wrapper.py index 90351bd69..ac5c2f8c2 100644 --- a/src/mjlab/rl/vecenv_wrapper.py +++ b/src/mjlab/rl/vecenv_wrapper.py @@ -1,4 +1,4 @@ -from typing import cast +from typing import Any, cast import gymnasium as gym import torch @@ -9,12 +9,16 @@ class RslRlVecEnvWrapper(VecEnv): - def __init__(self, env: ManagerBasedRlEnv, clip_actions: float | None = None): + def __init__( + self, + env: gym.Env, + clip_actions: float | None = None, + ): self.env = env self.clip_actions = clip_actions self.num_envs = self.unwrapped.num_envs - self.device = self.unwrapped.device + self.device = torch.device(self.unwrapped.device) self.max_episode_length = self.unwrapped.max_episode_length self.num_actions = self.unwrapped.action_manager.total_action_dim self._modify_action_space() @@ -44,7 +48,9 @@ def class_name(cls) -> str: @property def unwrapped(self) -> ManagerBasedRlEnv: - return cast(ManagerBasedRlEnv, self.env.unwrapped) + out = self.env.unwrapped + assert isinstance(out, ManagerBasedRlEnv) + return out # Properties. @@ -53,7 +59,7 @@ def episode_length_buf(self) -> torch.Tensor: return self.unwrapped.episode_length_buf @episode_length_buf.setter - def episode_length_buf(self, value: torch.Tensor): + def episode_length_buf(self, value: torch.Tensor) -> None: # type: ignore self.unwrapped.episode_length_buf = value def seed(self, seed: int = -1) -> int: @@ -61,11 +67,13 @@ def seed(self, seed: int = -1) -> int: def get_observations(self) -> TensorDict: obs_dict = self.unwrapped.observation_manager.compute() - return TensorDict(obs_dict, batch_size=[self.num_envs]) + return TensorDict(cast(dict[str, Any], obs_dict), batch_size=[self.num_envs]) def reset(self) -> tuple[TensorDict, dict]: obs_dict, extras = self.env.reset() - return TensorDict(obs_dict, batch_size=[self.num_envs]), extras + return TensorDict( + cast(dict[str, Any], obs_dict), batch_size=[self.num_envs] + ), extras def step( self, actions: torch.Tensor @@ -73,10 +81,18 @@ def step( if self.clip_actions is not None: actions = torch.clamp(actions, -self.clip_actions, self.clip_actions) obs_dict, rew, terminated, truncated, extras = self.env.step(actions) - dones = (terminated | truncated).to(dtype=torch.long) + term_or_trunc = terminated | truncated + assert isinstance(rew, torch.Tensor) + assert isinstance(term_or_trunc, torch.Tensor) + dones = term_or_trunc.to(dtype=torch.long) if not self.cfg.is_finite_horizon: extras["time_outs"] = truncated - return TensorDict(obs_dict, batch_size=[self.num_envs]), rew, dones, extras + return ( + TensorDict(cast(dict[str, Any], obs_dict), batch_size=[self.num_envs]), + rew, + dones, + extras, + ) def close(self) -> None: return self.env.close() @@ -87,9 +103,9 @@ def _modify_action_space(self) -> None: if self.clip_actions is None: return - self.env.unwrapped.single_action_space = gym.spaces.Box( + self.unwrapped.single_action_space = gym.spaces.Box( low=-self.clip_actions, high=self.clip_actions, shape=(self.num_actions,) ) - self.env.unwrapped.action_space = gym.vector.utils.batch_space( - self.env.unwrapped.single_action_space, self.num_envs + self.unwrapped.action_space = gym.vector.utils.batch_space( + self.unwrapped.single_action_space, self.num_envs ) diff --git a/src/mjlab/sensors/contact_sensor/contact_sensor.py b/src/mjlab/sensors/contact_sensor/contact_sensor.py index c0b99f7ca..924ab7f89 100644 --- a/src/mjlab/sensors/contact_sensor/contact_sensor.py +++ b/src/mjlab/sensors/contact_sensor/contact_sensor.py @@ -22,11 +22,12 @@ class ContactSensor(SensorBase): def __init__(self, cfg: ContactSensorCfg): super().__init__(cfg) - self._data = ContactSensorData() + self._data: ContactSensorData | None = None @property def data(self) -> ContactSensorData: self._update_outdated_buffers() + assert self._data is not None return self._data @property @@ -54,6 +55,8 @@ def find_bodies( def compute_first_contact(self, dt: float, abs_tol: float = 1.0e-8) -> torch.Tensor: if not self.cfg.track_air_time: raise RuntimeError() + assert self.data.current_contact_time is not None + assert self.data.current_air_time is not None currently_in_contact = self.data.current_contact_time > 0.0 less_than_dt_in_contact = self.data.current_contact_time < (dt + abs_tol) return currently_in_contact * less_than_dt_in_contact @@ -61,6 +64,7 @@ def compute_first_contact(self, dt: float, abs_tol: float = 1.0e-8) -> torch.Ten def compute_first_air(self, dt: float, abs_tol: float = 1.0e-8) -> torch.Tensor: if not self.cfg.track_air_time: raise RuntimeError() + assert self.data.current_air_time is not None currently_detached = self.data.current_air_time > 0.0 less_than_dt_detached = self.data.current_air_time < (dt + abs_tol) return currently_detached * less_than_dt_detached @@ -106,11 +110,9 @@ def initialize( self.geom_to_body_map = torch.tensor(geom_to_body_map, device=device) # Prepare data buffers. - self._data.net_forces_w = torch.zeros( - self._num_envs, self._num_bodies, 3, device=self._device - ) + net_forces_w = torch.zeros(self._num_envs, self._num_bodies, 3, device=self._device) if self.cfg.history_length > 0: - self._data.net_forces_w_history = torch.zeros( + net_forces_w_history = torch.zeros( self._num_envs, self.cfg.history_length, self._num_bodies, @@ -118,28 +120,47 @@ def initialize( device=self._device, ) else: - self._data.net_forces_w_history = self._data.net_forces_w.unsqueeze(1) + net_forces_w_history = net_forces_w.unsqueeze(1) if self.cfg.track_air_time: - self._data.last_air_time = torch.zeros( - self._num_envs, self._num_bodies, device=self._device - ) - self._data.current_air_time = torch.zeros( - self._num_envs, self._num_bodies, device=self._device - ) - self._data.last_contact_time = torch.zeros( - self._num_envs, self._num_bodies, device=self._device + self._data = ContactSensorData( + net_forces_w=net_forces_w, + net_forces_w_history=net_forces_w_history, + last_air_time=torch.zeros( + self._num_envs, self._num_bodies, device=self._device + ), + current_air_time=torch.zeros( + self._num_envs, self._num_bodies, device=self._device + ), + last_contact_time=torch.zeros( + self._num_envs, self._num_bodies, device=self._device + ), + current_contact_time=torch.zeros( + self._num_envs, self._num_bodies, device=self._device + ), ) - self._data.current_contact_time = torch.zeros( - self._num_envs, self._num_bodies, device=self._device + else: + self._data = ContactSensorData( + net_forces_w=net_forces_w, + net_forces_w_history=net_forces_w_history, + last_air_time=None, + current_air_time=None, + last_contact_time=None, + current_contact_time=None, ) def reset(self, env_ids: torch.Tensor | slice | None = None): super().reset(env_ids) if env_ids is None: env_ids = slice(None) + + assert self._data is not None self._data.net_forces_w[env_ids] = 0.0 self._data.net_forces_w_history[env_ids] = 0.0 if self.cfg.track_air_time: + assert self._data.current_air_time is not None + assert self._data.last_air_time is not None + assert self._data.current_contact_time is not None + assert self._data.last_contact_time is not None self._data.current_air_time[env_ids] = 0.0 self._data.last_air_time[env_ids] = 0.0 self._data.current_contact_time[env_ids] = 0.0 @@ -151,6 +172,7 @@ def _update_buffers_impl(self, env_ids: torch.Tensor | slice | None = None): # env_ids = slice(None) if env_ids is None: env_ids = slice(None) + assert self._data is not None self._data.net_forces_w[env_ids] = 0.0 self._compute_contact_forces(env_ids) self._update_force_history(env_ids) @@ -159,6 +181,7 @@ def _update_buffers_impl(self, env_ids: torch.Tensor | slice | None = None): def _compute_contact_forces(self, env_ids): """Compute net contact forces for each body from geom contacts.""" + assert self._data is not None body_forces = torch.zeros( (len(self._body_ids), 3), device=self._device, dtype=self._data.net_forces_w.dtype ) @@ -201,8 +224,8 @@ def _get_contact_forces(self, valid_contacts): force = wp.zeros(num_contacts, dtype=wp.spatial_vector) # type: ignore contact_ids = wp.from_torch(valid_contacts["indices"].int(), dtype=wp.int32) mjwarp.contact_force( - m=self._wp_model.struct, - d=self._wp_data.struct, + m=self._wp_model.struct, # type: ignore + d=self._wp_data.struct, # type: ignore contact_ids=contact_ids, to_world_frame=True, force=force, @@ -217,6 +240,7 @@ def _extract_normal_forces(self, forces, frames): def _update_force_history(self, env_ids): """Update force history buffer if configured.""" + assert self._data is not None if self.cfg.history_length > 0: history = self._data.net_forces_w_history[env_ids] self._data.net_forces_w_history[env_ids] = history.roll(1, dims=1) @@ -224,6 +248,7 @@ def _update_force_history(self, env_ids): def _update_contact_timing(self, env_ids): """Track air and contact time for each body.""" + assert self._data is not None elapsed_time = self._timestamp[env_ids] - self._timestamp_last_update[env_ids] elapsed_time = elapsed_time.unsqueeze(-1) @@ -232,6 +257,8 @@ def _update_contact_timing(self, env_ids): is_contact = force_magnitudes > self.cfg.force_threshold # Detect state transitions. + assert self._data.current_air_time is not None + assert self._data.current_contact_time is not None is_first_contact = (self._data.current_air_time[env_ids] > 0) * is_contact is_first_detached = (self._data.current_contact_time[env_ids] > 0) * ~is_contact @@ -241,6 +268,9 @@ def _update_contact_timing(self, env_ids): def _update_air_time(self, env_ids, elapsed_time, is_contact, is_first_contact): """Update air time counters.""" # Save total air time when first making contact. + assert self._data is not None + assert self._data.current_air_time is not None + assert self._data.last_air_time is not None self._data.last_air_time[env_ids] = torch.where( is_first_contact, self._data.current_air_time[env_ids] + elapsed_time, @@ -257,6 +287,9 @@ def _update_air_time(self, env_ids, elapsed_time, is_contact, is_first_contact): def _update_contact_time(self, env_ids, elapsed_time, is_contact, is_first_detached): """Update contact time counters.""" # Save total contact time when first detaching. + assert self._data is not None + assert self._data.current_contact_time is not None + assert self._data.last_contact_time is not None self._data.last_contact_time[env_ids] = torch.where( is_first_detached, self._data.current_contact_time[env_ids] + elapsed_time, diff --git a/src/mjlab/sensors/contact_sensor/contact_sensor_data.py b/src/mjlab/sensors/contact_sensor/contact_sensor_data.py index 15e5f307c..ef80a935a 100644 --- a/src/mjlab/sensors/contact_sensor/contact_sensor_data.py +++ b/src/mjlab/sensors/contact_sensor/contact_sensor_data.py @@ -7,9 +7,9 @@ @dataclass class ContactSensorData: - net_forces_w: torch.Tensor | None = None - net_forces_w_history: torch.Tensor | None = None - last_air_time: torch.Tensor | None = None - current_air_time: torch.Tensor | None = None - last_contact_time: torch.Tensor | None = None - current_contact_time: torch.Tensor | None = None + net_forces_w: torch.Tensor + net_forces_w_history: torch.Tensor + last_air_time: torch.Tensor | None + current_air_time: torch.Tensor | None + last_contact_time: torch.Tensor | None + current_contact_time: torch.Tensor | None diff --git a/src/mjlab/sim/sim_data.py b/src/mjlab/sim/sim_data.py index c633a0930..96be8775a 100644 --- a/src/mjlab/sim/sim_data.py +++ b/src/mjlab/sim/sim_data.py @@ -17,7 +17,7 @@ def __init__(self, wp_array: wp.array) -> None: """Initialize the tensor proxy with a Warp array.""" self._wp_array = wp_array self._tensor = wp.to_torch(wp_array) - self._is_cuda = not self._wp_array.device.is_cpu + self._is_cuda = not self._wp_array.device.is_cpu # type: ignore self._torch_stream = self._setup_stream() def _setup_stream(self) -> Optional[torch.cuda.Stream]: diff --git a/src/mjlab/sim/sim_data_test.py b/src/mjlab/sim/sim_data_test.py index 4926b4b43..e558eaa72 100644 --- a/src/mjlab/sim/sim_data_test.py +++ b/src/mjlab/sim/sim_data_test.py @@ -43,7 +43,7 @@ def test_arithmetic_ops(self): def test_torch_func_interception(self): """Test that torch functions work with TensorProxy.""" - result = torch.sum(self.proxy) + result = torch.sum(self.proxy) # type: ignore expected = torch.sum(self.proxy._tensor) self.assertTrue(torch.allclose(result, expected)) @@ -75,7 +75,7 @@ def test_setting_from_tensor(self): """Test setting array from PyTorch tensor.""" new_tensor = torch.tensor([[1.0, 2.0, 3.0], [4.0, 5.0, 6.0]], device=self.device) self.warp_tensor.qpos = new_tensor - self.assertTrue(torch.allclose(self.warp_tensor.qpos._tensor, new_tensor)) + self.assertTrue(torch.allclose(self.warp_tensor.qpos._tensor, new_tensor)) # type: ignore def test_end_to_end_workflow(self): """Test a realistic usage workflow.""" diff --git a/src/mjlab/tasks/locomotion/velocity/mdp/rewards.py b/src/mjlab/tasks/locomotion/velocity/mdp/rewards.py index 5949d6eb5..1fe9bf771 100644 --- a/src/mjlab/tasks/locomotion/velocity/mdp/rewards.py +++ b/src/mjlab/tasks/locomotion/velocity/mdp/rewards.py @@ -24,6 +24,7 @@ def feet_air_time( first_contact = contact_sensor.compute_first_contact(env.step_dt)[ :, sensor_cfg.body_ids ] + assert contact_sensor.data.last_air_time is not None last_air_time = contact_sensor.data.last_air_time[:, sensor_cfg.body_ids] reward = torch.sum((last_air_time - threshold) * first_contact, dim=1) reward *= ( diff --git a/src/mjlab/tasks/locomotion/velocity/mdp/velocity_command.py b/src/mjlab/tasks/locomotion/velocity/mdp/velocity_command.py index e615fe7ec..f6a20dc1d 100644 --- a/src/mjlab/tasks/locomotion/velocity/mdp/velocity_command.py +++ b/src/mjlab/tasks/locomotion/velocity/mdp/velocity_command.py @@ -3,7 +3,6 @@ from dataclasses import dataclass from typing import ( TYPE_CHECKING, - Sequence, ) import mujoco @@ -16,13 +15,13 @@ from mjlab.third_party.isaaclab.isaaclab.utils.math import matrix_from_quat, wrap_to_pi if TYPE_CHECKING: - from mjlab.envs.manager_based_env import ManagerBasedEnv + from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv class UniformVelocityCommand(CommandTerm): cfg: UniformVelocityCommandCfg - def __init__(self, cfg: UniformVelocityCommandCfg, env: ManagerBasedEnv): + def __init__(self, cfg: UniformVelocityCommandCfg, env: ManagerBasedRlEnv): super().__init__(cfg, env) if self.cfg.heading_command and self.cfg.ranges.heading is None: @@ -60,7 +59,7 @@ def _update_metrics(self) -> None: / max_command_step ) - def _resample_command(self, env_ids: Sequence[int]) -> None: + def _resample_command(self, env_ids: torch.Tensor) -> None: r = torch.empty(len(env_ids), device=self.device) self.vel_command_b[env_ids, 0] = r.uniform_(*self.cfg.ranges.lin_vel_x) self.vel_command_b[env_ids, 1] = r.uniform_(*self.cfg.ranges.lin_vel_y) diff --git a/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py b/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py index 1ba5ac3d7..cf926e291 100644 --- a/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py +++ b/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py @@ -178,7 +178,7 @@ class EventCfg: "asset_cfg": SceneEntityCfg("robot", joint_names=[".*"]), }, ) - push_robot: EventTerm = term( + push_robot: EventTerm | None = term( EventTerm, func=mdp.push_by_setting_velocity, mode="interval", diff --git a/src/mjlab/tasks/tracking/rl/exporter.py b/src/mjlab/tasks/tracking/rl/exporter.py index 668eaf3fb..420aa091f 100644 --- a/src/mjlab/tasks/tracking/rl/exporter.py +++ b/src/mjlab/tasks/tracking/rl/exporter.py @@ -5,6 +5,7 @@ import torch from mjlab.envs import ManagerBasedRlEnv +from mjlab.envs.mdp.actions.joint_actions import JointAction from mjlab.tasks.tracking.mdp import MotionCommand from mjlab.third_party.isaaclab.isaaclab_rl.rsl_rl.exporter import _OnnxPolicyExporter @@ -38,7 +39,7 @@ def __init__( self.body_ang_vel_w = cmd.motion.body_ang_vel_w.to("cpu") self.time_step_total = self.joint_pos.shape[0] - def forward(self, x, time_step): + def forward(self, x, time_step): # pyright: ignore [reportIncompatibleMethodOverride] time_step_clamped = torch.clamp( time_step.long().squeeze(-1), max=self.time_step_total - 1 ) @@ -91,6 +92,8 @@ def attach_onnx_metadata( env: ManagerBasedRlEnv, run_path: str, path: str, filename="policy.onnx" ) -> None: onnx_path = os.path.join(path, filename) + joint_action = env.action_manager.get_term("joint_pos") + assert isinstance(joint_action, JointAction) metadata = { "run_path": run_path, "joint_names": env.scene["robot"].data.joint_names, @@ -99,7 +102,9 @@ def attach_onnx_metadata( "default_joint_pos": env.scene["robot"].data.default_joint_pos[0].cpu().tolist(), "command_names": env.command_manager.active_terms, "observation_names": env.observation_manager.active_terms["policy"], - "action_scale": env.action_manager.get_term("joint_pos")._scale[0].cpu().tolist(), + "action_scale": joint_action._scale[0].cpu().tolist() + if isinstance(joint_action._scale, torch.Tensor) + else joint_action._scale, } model = onnx.load(onnx_path) diff --git a/src/mjlab/tasks/tracking/tracking_env_cfg.py b/src/mjlab/tasks/tracking/tracking_env_cfg.py index 7bf57a1f6..fac22d303 100644 --- a/src/mjlab/tasks/tracking/tracking_env_cfg.py +++ b/src/mjlab/tasks/tracking/tracking_env_cfg.py @@ -2,7 +2,6 @@ from mjlab.asset_zoo.terrains.flat_terrain import FLAT_TERRAIN_CFG from mjlab.envs import ManagerBasedRlEnvCfg -from mjlab.managers.manager_term_config import ActionTermCfg as ActionTerm from mjlab.managers.manager_term_config import EventTermCfg as EventTerm from mjlab.managers.manager_term_config import ObservationGroupCfg as ObsGroup from mjlab.managers.manager_term_config import ObservationTermCfg as ObsTerm @@ -92,7 +91,7 @@ class CommandsCfg: @dataclass class ActionCfg: - joint_pos: ActionTerm = term( + joint_pos: mdp.JointPositionActionCfg = term( mdp.JointPositionActionCfg, asset_name="robot", actuator_names=[".*"], @@ -166,7 +165,7 @@ class PrivilegedCfg(ObsGroup): @dataclass class EventCfg: - push_robot: EventTerm = term( + push_robot: EventTerm | None = term( EventTerm, func=mdp.push_by_setting_velocity, mode="interval", diff --git a/src/mjlab/utils/noise/__init__.py b/src/mjlab/utils/noise/__init__.py index d6f80f5ac..5eb7353d0 100644 --- a/src/mjlab/utils/noise/__init__.py +++ b/src/mjlab/utils/noise/__init__.py @@ -9,9 +9,6 @@ from mjlab.utils.noise.noise_model import ( NoiseModel, NoiseModelWithAdditiveBias, - constant_noise, - gaussian_noise, - uniform_noise, ) __all__ = ( @@ -25,7 +22,4 @@ # Models. "NoiseModel", "NoiseModelWithAdditiveBias", - "constant_noise", - "gaussian_noise", - "uniform_noise", ) diff --git a/src/mjlab/utils/noise/noise_cfg.py b/src/mjlab/utils/noise/noise_cfg.py index e904e0b28..9c821d4a5 100644 --- a/src/mjlab/utils/noise/noise_cfg.py +++ b/src/mjlab/utils/noise/noise_cfg.py @@ -1,63 +1,107 @@ from __future__ import annotations -from dataclasses import dataclass, field -from typing import Callable, Literal, TypeVar +import abc +from dataclasses import dataclass +from typing import ClassVar, Literal import torch +from typing_extensions import override from mjlab.utils.noise import noise_model -T = TypeVar("T", bound="NoiseCfg") +def _ensure_tensor_device( + value: torch.Tensor | float, device: torch.device +) -> torch.Tensor | float: + """Ensure tensor is on the correct device, leave scalars unchanged.""" + if isinstance(value, torch.Tensor): + return value.to(device=device) + return value -@dataclass -class NoiseCfg: + +@dataclass(kw_only=True) +class NoiseCfg(abc.ABC): """Base configuration for a noise term.""" - func: Callable[[torch.Tensor, "NoiseCfg"], torch.Tensor] | None = None operation: Literal["add", "scale", "abs"] = "add" - def __post_init__(self): - if self.func is None: - raise ValueError("func must be specified for NoiseCfg") + @abc.abstractmethod + def apply(self, data: torch.Tensor) -> torch.Tensor: + """Apply noise to the input data.""" @dataclass class ConstantNoiseCfg(NoiseCfg): - func: Callable[[torch.Tensor, "ConstantNoiseCfg"], torch.Tensor] = field( - default_factory=lambda: noise_model.constant_noise - ) bias: torch.Tensor | float = 0.0 + @override + def apply(self, data: torch.Tensor) -> torch.Tensor: + self.bias = _ensure_tensor_device(self.bias, data.device) + + if self.operation == "add": + return data + self.bias + elif self.operation == "scale": + return data * self.bias + elif self.operation == "abs": + return torch.zeros_like(data) + self.bias + else: + raise ValueError(f"Unsupported noise operation: {self.operation}") + @dataclass class UniformNoiseCfg(NoiseCfg): - func: Callable[[torch.Tensor, "UniformNoiseCfg"], torch.Tensor] = field( - default_factory=lambda: noise_model.uniform_noise - ) n_min: torch.Tensor | float = -1.0 n_max: torch.Tensor | float = 1.0 def __post_init__(self): - super().__post_init__() if isinstance(self.n_min, (int, float)) and isinstance(self.n_max, (int, float)): if self.n_min >= self.n_max: raise ValueError(f"n_min ({self.n_min}) must be less than n_max ({self.n_max})") + @override + def apply(self, data: torch.Tensor) -> torch.Tensor: + self.n_min = _ensure_tensor_device(self.n_min, data.device) + self.n_max = _ensure_tensor_device(self.n_max, data.device) + + # Generate uniform noise in [0, 1) and scale to [n_min, n_max). + noise = torch.rand_like(data) * (self.n_max - self.n_min) + self.n_min + + if self.operation == "add": + return data + noise + elif self.operation == "scale": + return data * noise + elif self.operation == "abs": + return noise + else: + raise ValueError(f"Unsupported noise operation: {self.operation}") + @dataclass class GaussianNoiseCfg(NoiseCfg): - func: Callable[[torch.Tensor, "GaussianNoiseCfg"], torch.Tensor] = field( - default_factory=lambda: noise_model.gaussian_noise - ) mean: torch.Tensor | float = 0.0 std: torch.Tensor | float = 1.0 def __post_init__(self): - super().__post_init__() if isinstance(self.std, (int, float)) and self.std <= 0: raise ValueError(f"std ({self.std}) must be positive") + @override + def apply(self, data: torch.Tensor) -> torch.Tensor: + self.mean = _ensure_tensor_device(self.mean, data.device) + self.std = _ensure_tensor_device(self.std, data.device) + + # Generate standard normal noise and scale. + noise = self.mean + self.std * torch.randn_like(data) + + if self.operation == "add": + return data + noise + elif self.operation == "scale": + return data * noise + elif self.operation == "abs": + return noise + else: + raise ValueError(f"Unsupported noise operation: {self.operation}") + ## # Noise models. @@ -68,38 +112,25 @@ def __post_init__(self): class NoiseModelCfg: """Configuration for a noise model.""" - class_type: type = field(default_factory=lambda: noise_model.NoiseModel) - noise_cfg: Callable[[torch.Tensor, "NoiseCfg"], torch.Tensor] | None = None - func: Callable[[torch.Tensor], torch.Tensor] | None = None + noise_cfg: NoiseCfg - def __post_init__(self): - if self.noise_cfg is None: - raise ValueError("noise_cfg must be specified for NoiseModelCfg") + class_type: ClassVar[type[noise_model.NoiseModel]] = noise_model.NoiseModel - if not issubclass(self.class_type, noise_model.NoiseModel): - raise ValueError( - f"class_type must be a subclass of NoiseModel, got {self.class_type}" - ) + def __init_subclass__(cls, class_type: type[noise_model.NoiseModel]): + cls.class_type = class_type @dataclass(kw_only=True) -class NoiseModelWithAdditiveBiasCfg(NoiseModelCfg): +class NoiseModelWithAdditiveBiasCfg( + NoiseModelCfg, class_type=noise_model.NoiseModelWithAdditiveBias +): """Configuration for an additive Gaussian noise with bias model.""" - class_type: type = field( - default_factory=lambda: noise_model.NoiseModelWithAdditiveBias - ) - bias_noise_cfg: Callable[[torch.Tensor, "NoiseCfg"], torch.Tensor] | None = None + bias_noise_cfg: NoiseCfg | None = None sample_bias_per_component: bool = True def __post_init__(self): - super().__post_init__() if self.bias_noise_cfg is None: raise ValueError( "bias_noise_cfg must be specified for NoiseModelWithAdditiveBiasCfg" ) - - if not issubclass(self.class_type, noise_model.NoiseModelWithAdditiveBias): - raise ValueError( - f"class_type must be a subclass of NoiseModelWithAdditiveBias, got {self.class_type}" - ) diff --git a/src/mjlab/utils/noise/noise_model.py b/src/mjlab/utils/noise/noise_model.py index a9e8deaa7..6e75db450 100644 --- a/src/mjlab/utils/noise/noise_model.py +++ b/src/mjlab/utils/noise/noise_model.py @@ -3,77 +3,12 @@ from typing import TYPE_CHECKING import torch +from typing_extensions import override if TYPE_CHECKING: from mjlab.utils.noise import noise_cfg -## -# Noise as functions. -## - - -def _ensure_tensor_device( - value: torch.Tensor | float, device: torch.device -) -> torch.Tensor | float: - """Ensure tensor is on the correct device, leave scalars unchanged.""" - if isinstance(value, torch.Tensor): - return value.to(device=device) - return value - - -def constant_noise(data: torch.Tensor, cfg: noise_cfg.ConstantNoiseCfg) -> torch.Tensor: - cfg.bias = _ensure_tensor_device(cfg.bias, data.device) - - if cfg.operation == "add": - return data + cfg.bias - elif cfg.operation == "scale": - return data * cfg.bias - elif cfg.operation == "abs": - return torch.zeros_like(data) + cfg.bias - else: - raise ValueError(f"Unsupported noise operation: {cfg.operation}") - - -def uniform_noise(data: torch.Tensor, cfg: noise_cfg.UniformNoiseCfg) -> torch.Tensor: - cfg.n_min = _ensure_tensor_device(cfg.n_min, data.device) - cfg.n_max = _ensure_tensor_device(cfg.n_max, data.device) - - # Generate uniform noise in [0, 1) and scale to [n_min, n_max). - noise = torch.rand_like(data) * (cfg.n_max - cfg.n_min) + cfg.n_min - - if cfg.operation == "add": - return data + noise - elif cfg.operation == "scale": - return data * noise - elif cfg.operation == "abs": - return noise - else: - raise ValueError(f"Unsupported noise operation: {cfg.operation}") - - -def gaussian_noise(data: torch.Tensor, cfg: noise_cfg.GaussianNoiseCfg) -> torch.Tensor: - cfg.mean = _ensure_tensor_device(cfg.mean, data.device) - cfg.std = _ensure_tensor_device(cfg.std, data.device) - - # Generate standard normal noise and scale. - noise = cfg.mean + cfg.std * torch.randn_like(data) - - if cfg.operation == "add": - return data + noise - elif cfg.operation == "scale": - return data * noise - elif cfg.operation == "abs": - return noise - else: - raise ValueError(f"Unsupported noise operation: {cfg.operation}") - - -## -# Noise as classes. -## - - class NoiseModel: """Base class for noise models.""" @@ -88,12 +23,13 @@ def __init__( if not hasattr(noise_model_cfg, "noise_cfg") or noise_model_cfg.noise_cfg is None: raise ValueError("NoiseModelCfg must have a valid noise_cfg") - def reset(self, env_ids: torch.Tensor | slice | None = None): + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: """Reset noise model state. Override in subclasses if needed.""" def __call__(self, data: torch.Tensor) -> torch.Tensor: """Apply noise to input data.""" - return self._noise_model_cfg.noise_cfg.func(data, self._noise_model_cfg.noise_cfg) + assert self._noise_model_cfg.noise_cfg is not None + return self._noise_model_cfg.noise_cfg.apply(data) class NoiseModelWithAdditiveBias(NoiseModel): @@ -123,13 +59,12 @@ def __init__( self._num_components: int | None = None self._bias_initialized = False - def reset(self, env_ids: torch.Tensor | slice | None = None): + @override + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: """Reset bias values for specified environments.""" indices = slice(None) if env_ids is None else env_ids # Sample new bias values. - self._bias[indices] = self._bias_noise_cfg.func( - self._bias[indices], self._bias_noise_cfg - ) + self._bias[indices] = self._bias_noise_cfg.apply(self._bias[indices]) def _initialize_bias_shape(self, data_shape: torch.Size) -> None: """Initialize bias tensor shape based on data and configuration.""" @@ -141,6 +76,7 @@ def _initialize_bias_shape(self, data_shape: torch.Size) -> None: # Resample bias with new shape. self.reset() + @override def __call__(self, data: torch.Tensor) -> torch.Tensor: """Apply noise and additive bias to input data.""" self._initialize_bias_shape(data.shape) diff --git a/src/mjlab/utils/random.py b/src/mjlab/utils/random.py index 443d6e461..2d8cc4a7b 100644 --- a/src/mjlab/utils/random.py +++ b/src/mjlab/utils/random.py @@ -12,7 +12,7 @@ def seed_rng(seed: int, torch_deterministic: bool = False) -> None: random.seed(seed) np.random.seed(seed) - wp.rand_init(seed) + wp.rand_init(wp.int32(seed)) # Ref: https://docs.pytorch.org/docs/stable/notes/randomness.html torch.manual_seed(seed) # Seed RNG for all devices. diff --git a/src/mjlab/viewer/base.py b/src/mjlab/viewer/base.py index 3c0a4dae1..f569dc88e 100644 --- a/src/mjlab/viewer/base.py +++ b/src/mjlab/viewer/base.py @@ -56,13 +56,16 @@ class EnvProtocol(Protocol): """Protocol for environment interface.""" device: torch.device - cfg: ManagerBasedEnvCfg - def get_observations(self) -> torch.Tensor: ... + # @property is convenient for treating cfg as read-only. This makes typing easier. + @property + def cfg(self) -> ManagerBasedEnvCfg: ... + + def get_observations(self) -> Any: ... - def step(self, actions: torch.Tensor) -> tuple[torch.Tensor, ...]: ... + def step(self, actions: torch.Tensor) -> tuple[Any, ...]: ... - def reset(self) -> torch.Tensor: ... + def reset(self) -> Any: ... @property def unwrapped(self) -> Any: ... diff --git a/src/mjlab/viewer/native.py b/src/mjlab/viewer/native.py index d22a49817..33ad63441 100644 --- a/src/mjlab/viewer/native.py +++ b/src/mjlab/viewer/native.py @@ -123,6 +123,7 @@ def setup(self) -> None: # Create visualization data for rendering multiple environments. if self.render_all_envs and self.env.unwrapped.num_envs > 1: + assert self.mjm is not None self.vd = mujoco.MjData(self.mjm) # Setup visualization options. @@ -132,6 +133,8 @@ def setup(self) -> None: self._env_origins = compute_env_origins_grid(sim.num_envs, env_spacing=2.0) + assert self.mjm is not None + assert self.mjd is not None self.viewer = mujoco.viewer.launch_passive( self.mjm, self.mjd, key_callback=self.key_callback ) @@ -218,10 +221,12 @@ def sync_env_to_viewer(self) -> None: sim_data = self.env.unwrapped.sim.data # Copy primary environment state to viewer. + assert self.mjd is not None self.mjd.qpos[:] = sim_data.qpos[self.env_idx].cpu().numpy() self.mjd.qvel[:] = sim_data.qvel[self.env_idx].cpu().numpy() # Forward dynamics to update derived quantities. + assert self.mjm is not None mujoco.mj_forward(self.mjm, self.mjd) def sync_viewer_to_env(self) -> None: @@ -230,6 +235,7 @@ def sync_viewer_to_env(self) -> None: return # Copy perturbation forces from viewer to environment. + assert self.mjd is not None xfrc_applied = torch.tensor( self.mjd.xfrc_applied, dtype=torch.float, device=self.env.device ) @@ -237,6 +243,7 @@ def sync_viewer_to_env(self) -> None: def update_visualizations(self) -> None: """Update additional visualizations.""" + assert self.viewer is not None user_scn = self.viewer.user_scn if user_scn is None: return @@ -262,6 +269,11 @@ def update_visualizations(self) -> None: # Apply offset. # TODO(kevin): Make this less hacky. self.vd.qpos[:3] += self._env_origins[i] + + assert self.mjm is not None + assert self.vopt is not None + assert self.pert is not None + assert self.catmask is not None mujoco.mj_forward(self.mjm, self.vd) mujoco.mjv_addGeoms( self.mjm, self.vd, self.vopt, self.pert, self.catmask, user_scn diff --git a/typings/generate_mujoco_stubs.sh b/typings/generate_mujoco_stubs.sh new file mode 100755 index 000000000..521f96f6b --- /dev/null +++ b/typings/generate_mujoco_stubs.sh @@ -0,0 +1,21 @@ +#!/usr/bin/env bash + +# Generate type stubs for MuJoCo using pybind11-stubgen +# This helps suppress pyright errors for MuJoCo's C++ bindings + +set -e + +SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" + +echo "Installing pybind11-stubgen if not already installed..." +uv pip install -q pybind11-stubgen + +echo "Generating MuJoCo type stubs..." +uv run pybind11-stubgen mujoco -o "$SCRIPT_DIR" --ignore-all-errors +uv run pybind11-stubgen mujoco.viewer -o "$SCRIPT_DIR" --ignore-all-errors + +echo "MuJoCo stubs generated successfully in $SCRIPT_DIR/mujoco/" +echo "" +echo "Make sure your pyproject.toml includes:" +echo " [tool.pyright]" +echo " stubPath = \"typings\"" diff --git a/typings/mujoco/__init__.pyi b/typings/mujoco/__init__.pyi new file mode 100644 index 000000000..6f408ecfb --- /dev/null +++ b/typings/mujoco/__init__.pyi @@ -0,0 +1,1225 @@ +""" +Python bindings for MuJoCo. +""" + +from __future__ import annotations +import ctypes as ctypes +from mujoco._callbacks import get_mjcb_act_bias +from mujoco._callbacks import get_mjcb_act_dyn +from mujoco._callbacks import get_mjcb_act_gain +from mujoco._callbacks import get_mjcb_contactfilter +from mujoco._callbacks import get_mjcb_control +from mujoco._callbacks import get_mjcb_passive +from mujoco._callbacks import get_mjcb_sensor +from mujoco._callbacks import get_mjcb_time +from mujoco._callbacks import get_mju_user_free +from mujoco._callbacks import get_mju_user_malloc +from mujoco._callbacks import get_mju_user_warning +from mujoco._callbacks import set_mjcb_act_bias +from mujoco._callbacks import set_mjcb_act_dyn +from mujoco._callbacks import set_mjcb_act_gain +from mujoco._callbacks import set_mjcb_contactfilter +from mujoco._callbacks import set_mjcb_control +from mujoco._callbacks import set_mjcb_passive +from mujoco._callbacks import set_mjcb_sensor +from mujoco._callbacks import set_mjcb_time +from mujoco._callbacks import set_mju_user_free +from mujoco._callbacks import set_mju_user_malloc +from mujoco._callbacks import set_mju_user_warning +from mujoco._enums import mjtAlignFree +from mujoco._enums import mjtBias +from mujoco._enums import mjtBuiltin +from mujoco._enums import mjtButton +from mujoco._enums import mjtCamLight +from mujoco._enums import mjtCamera +from mujoco._enums import mjtCatBit +from mujoco._enums import mjtColorSpace +from mujoco._enums import mjtConDataField +from mujoco._enums import mjtCone +from mujoco._enums import mjtConstraint +from mujoco._enums import mjtConstraintState +from mujoco._enums import mjtDataType +from mujoco._enums import mjtDepthMap +from mujoco._enums import mjtDisableBit +from mujoco._enums import mjtDyn +from mujoco._enums import mjtEnableBit +from mujoco._enums import mjtEq +from mujoco._enums import mjtEvent +from mujoco._enums import mjtFlexSelf +from mujoco._enums import mjtFont +from mujoco._enums import mjtFontScale +from mujoco._enums import mjtFrame +from mujoco._enums import mjtFramebuffer +from mujoco._enums import mjtGain +from mujoco._enums import mjtGeom +from mujoco._enums import mjtGeomInertia +from mujoco._enums import mjtGridPos +from mujoco._enums import mjtInertiaFromGeom +from mujoco._enums import mjtIntegrator +from mujoco._enums import mjtItem +from mujoco._enums import mjtJacobian +from mujoco._enums import mjtJoint +from mujoco._enums import mjtLRMode +from mujoco._enums import mjtLabel +from mujoco._enums import mjtLightType +from mujoco._enums import mjtLimited +from mujoco._enums import mjtMark +from mujoco._enums import mjtMeshBuiltin +from mujoco._enums import mjtMeshInertia +from mujoco._enums import mjtMouse +from mujoco._enums import mjtObj +from mujoco._enums import mjtOrientation +from mujoco._enums import mjtPertBit +from mujoco._enums import mjtPluginCapabilityBit +from mujoco._enums import mjtRndFlag +from mujoco._enums import mjtSDFType +from mujoco._enums import mjtSameFrame +from mujoco._enums import mjtSection +from mujoco._enums import mjtSensor +from mujoco._enums import mjtSolver +from mujoco._enums import mjtStage +from mujoco._enums import mjtState +from mujoco._enums import mjtStereo +from mujoco._enums import mjtTaskStatus +from mujoco._enums import mjtTexture +from mujoco._enums import mjtTextureRole +from mujoco._enums import mjtTimer +from mujoco._enums import mjtTrn +from mujoco._enums import mjtVisFlag +from mujoco._enums import mjtWarning +from mujoco._enums import mjtWrap +from mujoco._functions import mj_Euler +from mujoco._functions import mj_RungeKutta +from mujoco._functions import mj_addContact +from mujoco._functions import mj_addM +from mujoco._functions import mj_angmomMat +from mujoco._functions import mj_applyFT +from mujoco._functions import mj_camlight +from mujoco._functions import mj_checkAcc +from mujoco._functions import mj_checkPos +from mujoco._functions import mj_checkVel +from mujoco._functions import mj_collision +from mujoco._functions import mj_comPos +from mujoco._functions import mj_comVel +from mujoco._functions import mj_compareFwdInv +from mujoco._functions import mj_constraintUpdate +from mujoco._functions import mj_contactForce +from mujoco._functions import mj_crb +from mujoco._functions import mj_defaultLROpt +from mujoco._functions import mj_defaultOption +from mujoco._functions import mj_defaultSolRefImp +from mujoco._functions import mj_defaultVisual +from mujoco._functions import mj_differentiatePos +from mujoco._functions import mj_energyPos +from mujoco._functions import mj_energyVel +from mujoco._functions import mj_factorM +from mujoco._functions import mj_flex +from mujoco._functions import mj_forward +from mujoco._functions import mj_forwardSkip +from mujoco._functions import mj_fullM +from mujoco._functions import mj_fwdAcceleration +from mujoco._functions import mj_fwdActuation +from mujoco._functions import mj_fwdConstraint +from mujoco._functions import mj_fwdPosition +from mujoco._functions import mj_fwdVelocity +from mujoco._functions import mj_geomDistance +from mujoco._functions import mj_getState +from mujoco._functions import mj_getTotalmass +from mujoco._functions import mj_id2name +from mujoco._functions import mj_implicit +from mujoco._functions import mj_integratePos +from mujoco._functions import mj_invConstraint +from mujoco._functions import mj_invPosition +from mujoco._functions import mj_invVelocity +from mujoco._functions import mj_inverse +from mujoco._functions import mj_inverseSkip +from mujoco._functions import mj_isDual +from mujoco._functions import mj_isPyramidal +from mujoco._functions import mj_isSparse +from mujoco._functions import mj_island +from mujoco._functions import mj_jac +from mujoco._functions import mj_jacBody +from mujoco._functions import mj_jacBodyCom +from mujoco._functions import mj_jacDot +from mujoco._functions import mj_jacGeom +from mujoco._functions import mj_jacPointAxis +from mujoco._functions import mj_jacSite +from mujoco._functions import mj_jacSubtreeCom +from mujoco._functions import mj_kinematics +from mujoco._functions import mj_loadAllPluginLibraries +from mujoco._functions import mj_loadPluginLibrary +from mujoco._functions import mj_local2Global +from mujoco._functions import mj_makeConstraint +from mujoco._functions import mj_makeM +from mujoco._functions import mj_mulJacTVec +from mujoco._functions import mj_mulJacVec +from mujoco._functions import mj_mulM +from mujoco._functions import mj_mulM2 +from mujoco._functions import mj_multiRay +from mujoco._functions import mj_name2id +from mujoco._functions import mj_normalizeQuat +from mujoco._functions import mj_objectAcceleration +from mujoco._functions import mj_objectVelocity +from mujoco._functions import mj_passive +from mujoco._functions import mj_printData +from mujoco._functions import mj_printFormattedData +from mujoco._functions import mj_printFormattedModel +from mujoco._functions import mj_printModel +from mujoco._functions import mj_printSchema +from mujoco._functions import mj_projectConstraint +from mujoco._functions import mj_ray +from mujoco._functions import mj_rayHfield +from mujoco._functions import mj_rayMesh +from mujoco._functions import mj_referenceConstraint +from mujoco._functions import mj_resetCallbacks +from mujoco._functions import mj_resetData +from mujoco._functions import mj_resetDataDebug +from mujoco._functions import mj_resetDataKeyframe +from mujoco._functions import mj_rne +from mujoco._functions import mj_rnePostConstraint +from mujoco._functions import mj_saveLastXML +from mujoco._functions import mj_saveModel +from mujoco._functions import mj_sensorAcc +from mujoco._functions import mj_sensorPos +from mujoco._functions import mj_sensorVel +from mujoco._functions import mj_setConst +from mujoco._functions import mj_setKeyframe +from mujoco._functions import mj_setLengthRange +from mujoco._functions import mj_setState +from mujoco._functions import mj_setTotalmass +from mujoco._functions import mj_sizeModel +from mujoco._functions import mj_solveM +from mujoco._functions import mj_solveM2 +from mujoco._functions import mj_stateSize +from mujoco._functions import mj_step +from mujoco._functions import mj_step1 +from mujoco._functions import mj_step2 +from mujoco._functions import mj_subtreeVel +from mujoco._functions import mj_tendon +from mujoco._functions import mj_transmission +from mujoco._functions import mj_version +from mujoco._functions import mj_versionString +from mujoco._functions import mjd_inverseFD +from mujoco._functions import mjd_quatIntegrate +from mujoco._functions import mjd_subQuat +from mujoco._functions import mjd_transitionFD +from mujoco._functions import mju_Halton +from mujoco._functions import mju_L1 +from mujoco._functions import mju_add +from mujoco._functions import mju_add3 +from mujoco._functions import mju_addScl +from mujoco._functions import mju_addScl3 +from mujoco._functions import mju_addTo +from mujoco._functions import mju_addTo3 +from mujoco._functions import mju_addToScl +from mujoco._functions import mju_addToScl3 +from mujoco._functions import mju_axisAngle2Quat +from mujoco._functions import mju_band2Dense +from mujoco._functions import mju_bandDiag +from mujoco._functions import mju_bandMulMatVec +from mujoco._functions import mju_boxQP +from mujoco._functions import mju_cholFactor +from mujoco._functions import mju_cholFactorBand +from mujoco._functions import mju_cholSolve +from mujoco._functions import mju_cholSolveBand +from mujoco._functions import mju_cholUpdate +from mujoco._functions import mju_clip +from mujoco._functions import mju_copy +from mujoco._functions import mju_copy3 +from mujoco._functions import mju_copy4 +from mujoco._functions import mju_cross +from mujoco._functions import mju_d2n +from mujoco._functions import mju_decodePyramid +from mujoco._functions import mju_dense2Band +from mujoco._functions import mju_dense2sparse +from mujoco._functions import mju_derivQuat +from mujoco._functions import mju_dist3 +from mujoco._functions import mju_dot +from mujoco._functions import mju_dot3 +from mujoco._functions import mju_eig3 +from mujoco._functions import mju_encodePyramid +from mujoco._functions import mju_euler2Quat +from mujoco._functions import mju_eye +from mujoco._functions import mju_f2n +from mujoco._functions import mju_fill +from mujoco._functions import mju_insertionSort +from mujoco._functions import mju_insertionSortInt +from mujoco._functions import mju_isBad +from mujoco._functions import mju_isZero +from mujoco._functions import mju_mat2Quat +from mujoco._functions import mju_mat2Rot +from mujoco._functions import mju_max +from mujoco._functions import mju_min +from mujoco._functions import mju_mulMatMat +from mujoco._functions import mju_mulMatMatT +from mujoco._functions import mju_mulMatTMat +from mujoco._functions import mju_mulMatTVec +from mujoco._functions import mju_mulMatTVec3 +from mujoco._functions import mju_mulMatVec +from mujoco._functions import mju_mulMatVec3 +from mujoco._functions import mju_mulPose +from mujoco._functions import mju_mulQuat +from mujoco._functions import mju_mulQuatAxis +from mujoco._functions import mju_mulVecMatVec +from mujoco._functions import mju_muscleBias +from mujoco._functions import mju_muscleDynamics +from mujoco._functions import mju_muscleGain +from mujoco._functions import mju_n2d +from mujoco._functions import mju_n2f +from mujoco._functions import mju_negPose +from mujoco._functions import mju_negQuat +from mujoco._functions import mju_norm +from mujoco._functions import mju_norm3 +from mujoco._functions import mju_normalize +from mujoco._functions import mju_normalize3 +from mujoco._functions import mju_normalize4 +from mujoco._functions import mju_printMat +from mujoco._functions import mju_printMatSparse +from mujoco._functions import mju_quat2Mat +from mujoco._functions import mju_quat2Vel +from mujoco._functions import mju_quatIntegrate +from mujoco._functions import mju_quatZ2Vec +from mujoco._functions import mju_rayFlex +from mujoco._functions import mju_rayGeom +from mujoco._functions import mju_raySkin +from mujoco._functions import mju_rotVecQuat +from mujoco._functions import mju_round +from mujoco._functions import mju_scl +from mujoco._functions import mju_scl3 +from mujoco._functions import mju_sigmoid +from mujoco._functions import mju_sign +from mujoco._functions import mju_sparse2dense +from mujoco._functions import mju_springDamper +from mujoco._functions import mju_sqrMatTD +from mujoco._functions import mju_standardNormal +from mujoco._functions import mju_str2Type +from mujoco._functions import mju_sub +from mujoco._functions import mju_sub3 +from mujoco._functions import mju_subFrom +from mujoco._functions import mju_subFrom3 +from mujoco._functions import mju_subQuat +from mujoco._functions import mju_sum +from mujoco._functions import mju_symmetrize +from mujoco._functions import mju_transformSpatial +from mujoco._functions import mju_transpose +from mujoco._functions import mju_trnVecPose +from mujoco._functions import mju_type2Str +from mujoco._functions import mju_unit4 +from mujoco._functions import mju_warningText +from mujoco._functions import mju_writeLog +from mujoco._functions import mju_writeNumBytes +from mujoco._functions import mju_zero +from mujoco._functions import mju_zero3 +from mujoco._functions import mju_zero4 +from mujoco._functions import mjv_addGeoms +from mujoco._functions import mjv_alignToCamera +from mujoco._functions import mjv_applyPerturbForce +from mujoco._functions import mjv_applyPerturbPose +from mujoco._functions import mjv_cameraInModel +from mujoco._functions import mjv_cameraInRoom +from mujoco._functions import mjv_connector +from mujoco._functions import mjv_defaultCamera +from mujoco._functions import mjv_defaultFigure +from mujoco._functions import mjv_defaultFreeCamera +from mujoco._functions import mjv_defaultOption +from mujoco._functions import mjv_defaultPerturb +from mujoco._functions import mjv_frustumHeight +from mujoco._functions import mjv_initGeom +from mujoco._functions import mjv_initPerturb +from mujoco._functions import mjv_makeLights +from mujoco._functions import mjv_model2room +from mujoco._functions import mjv_moveCamera +from mujoco._functions import mjv_moveModel +from mujoco._functions import mjv_movePerturb +from mujoco._functions import mjv_room2model +from mujoco._functions import mjv_select +from mujoco._functions import mjv_updateCamera +from mujoco._functions import mjv_updateScene +from mujoco._functions import mjv_updateSkin +from mujoco._render import MjrContext +from mujoco._render import MjrRect +from mujoco._render import mjr_addAux +from mujoco._render import mjr_blitAux +from mujoco._render import mjr_blitBuffer +from mujoco._render import mjr_changeFont +from mujoco._render import mjr_drawPixels +from mujoco._render import mjr_figure +from mujoco._render import mjr_findRect +from mujoco._render import mjr_finish +from mujoco._render import mjr_getError +from mujoco._render import mjr_label +from mujoco._render import mjr_maxViewport +from mujoco._render import mjr_overlay +from mujoco._render import mjr_readPixels +from mujoco._render import mjr_rectangle +from mujoco._render import mjr_render +from mujoco._render import mjr_resizeOffscreen +from mujoco._render import mjr_restoreBuffer +from mujoco._render import mjr_setAux +from mujoco._render import mjr_setBuffer +from mujoco._render import mjr_text +from mujoco._render import mjr_uploadHField +from mujoco._render import mjr_uploadMesh +from mujoco._render import mjr_uploadTexture +from mujoco._specs import MjByteVec +from mujoco._specs import MjCharVec +from mujoco._specs import MjDoubleVec +from mujoco._specs import MjFloatVec +from mujoco._specs import MjIntVec +from mujoco._specs import MjSpec +from mujoco._specs import MjStringVec +from mujoco._specs import MjVisualHeadlight +from mujoco._specs import MjVisualRgba +from mujoco._specs import MjsActuator +from mujoco._specs import MjsBody +from mujoco._specs import MjsCamera +from mujoco._specs import MjsCompiler +from mujoco._specs import MjsDefault +from mujoco._specs import MjsElement +from mujoco._specs import MjsEquality +from mujoco._specs import MjsExclude +from mujoco._specs import MjsFlex +from mujoco._specs import MjsFrame +from mujoco._specs import MjsGeom +from mujoco._specs import MjsHField +from mujoco._specs import MjsJoint +from mujoco._specs import MjsKey +from mujoco._specs import MjsLight +from mujoco._specs import MjsMaterial +from mujoco._specs import MjsMesh +from mujoco._specs import MjsNumeric +from mujoco._specs import MjsOrientation +from mujoco._specs import MjsPair +from mujoco._specs import MjsPlugin +from mujoco._specs import MjsSensor +from mujoco._specs import MjsSite +from mujoco._specs import MjsSkin +from mujoco._specs import MjsTendon +from mujoco._specs import MjsText +from mujoco._specs import MjsTexture +from mujoco._specs import MjsTuple +from mujoco._specs import MjsWrap +from mujoco._structs import MjContact +from mujoco._structs import MjData +from mujoco._structs import MjLROpt +from mujoco._structs import MjModel +from mujoco._structs import MjOption +from mujoco._structs import MjSolverStat +from mujoco._structs import MjStatistic +from mujoco._structs import MjTimerStat +from mujoco._structs import MjVisual +from mujoco._structs import MjWarningStat +from mujoco._structs import MjvCamera +from mujoco._structs import MjvFigure +from mujoco._structs import MjvGLCamera +from mujoco._structs import MjvGeom +from mujoco._structs import MjvLight +from mujoco._structs import MjvOption +from mujoco._structs import MjvPerturb +from mujoco._structs import MjvScene +from mujoco._structs import mjv_averageCamera +from mujoco.glfw import GLContext +from mujoco.renderer import Renderer +import os as os +import platform as platform +import subprocess as subprocess +import typing +from typing import Any +from typing import IO +import warnings as warnings +import zipfile as zipfile +from . import _callbacks +from . import _constants +from . import _enums +from . import _errors +from . import _functions +from . import _render +from . import _specs +from . import _structs +from . import gl_context +from . import glfw +from . import renderer + +__all__: list[str] = [ + "Any", + "FatalError", + "GLContext", + "HEADERS_DIR", + "IO", + "MjByteVec", + "MjCharVec", + "MjContact", + "MjData", + "MjDoubleVec", + "MjFloatVec", + "MjIntVec", + "MjLROpt", + "MjModel", + "MjOption", + "MjSolverStat", + "MjSpec", + "MjStatistic", + "MjStringVec", + "MjStruct", + "MjTimerStat", + "MjVisual", + "MjVisualHeadlight", + "MjVisualRgba", + "MjWarningStat", + "MjrContext", + "MjrRect", + "MjsActuator", + "MjsBody", + "MjsCamera", + "MjsCompiler", + "MjsDefault", + "MjsElement", + "MjsEquality", + "MjsExclude", + "MjsFlex", + "MjsFrame", + "MjsGeom", + "MjsHField", + "MjsJoint", + "MjsKey", + "MjsLight", + "MjsMaterial", + "MjsMesh", + "MjsNumeric", + "MjsOrientation", + "MjsPair", + "MjsPlugin", + "MjsSensor", + "MjsSite", + "MjsSkin", + "MjsTendon", + "MjsText", + "MjsTexture", + "MjsTuple", + "MjsWrap", + "MjvCamera", + "MjvFigure", + "MjvGLCamera", + "MjvGeom", + "MjvLight", + "MjvOption", + "MjvPerturb", + "MjvScene", + "PLUGINS_DIR", + "PLUGIN_HANDLES", + "Renderer", + "UnexpectedError", + "ctypes", + "from_zip", + "get_mjcb_act_bias", + "get_mjcb_act_dyn", + "get_mjcb_act_gain", + "get_mjcb_contactfilter", + "get_mjcb_control", + "get_mjcb_passive", + "get_mjcb_sensor", + "get_mjcb_time", + "get_mju_user_free", + "get_mju_user_malloc", + "get_mju_user_warning", + "gl_context", + "glfw", + "mjDISABLESTRING", + "mjENABLESTRING", + "mjFRAMESTRING", + "mjLABELSTRING", + "mjMAXCONPAIR", + "mjMAXIMP", + "mjMAXLIGHT", + "mjMAXLINE", + "mjMAXLINEPNT", + "mjMAXOVERLAY", + "mjMAXPLANEGRID", + "mjMAXVAL", + "mjMINIMP", + "mjMINMU", + "mjMINVAL", + "mjNBIAS", + "mjNDYN", + "mjNEQDATA", + "mjNGAIN", + "mjNGROUP", + "mjNIMP", + "mjNREF", + "mjNSOLVER", + "mjPI", + "mjRNDSTRING", + "mjTIMERSTRING", + "mjVERSION_HEADER", + "mjVISSTRING", + "mj_Euler", + "mj_RungeKutta", + "mj_addContact", + "mj_addM", + "mj_angmomMat", + "mj_applyFT", + "mj_camlight", + "mj_checkAcc", + "mj_checkPos", + "mj_checkVel", + "mj_collision", + "mj_comPos", + "mj_comVel", + "mj_compareFwdInv", + "mj_constraintUpdate", + "mj_contactForce", + "mj_crb", + "mj_defaultLROpt", + "mj_defaultOption", + "mj_defaultSolRefImp", + "mj_defaultVisual", + "mj_differentiatePos", + "mj_energyPos", + "mj_energyVel", + "mj_factorM", + "mj_flex", + "mj_forward", + "mj_forwardSkip", + "mj_fullM", + "mj_fwdAcceleration", + "mj_fwdActuation", + "mj_fwdConstraint", + "mj_fwdPosition", + "mj_fwdVelocity", + "mj_geomDistance", + "mj_getState", + "mj_getTotalmass", + "mj_id2name", + "mj_implicit", + "mj_integratePos", + "mj_invConstraint", + "mj_invPosition", + "mj_invVelocity", + "mj_inverse", + "mj_inverseSkip", + "mj_isDual", + "mj_isPyramidal", + "mj_isSparse", + "mj_island", + "mj_jac", + "mj_jacBody", + "mj_jacBodyCom", + "mj_jacDot", + "mj_jacGeom", + "mj_jacPointAxis", + "mj_jacSite", + "mj_jacSubtreeCom", + "mj_kinematics", + "mj_loadAllPluginLibraries", + "mj_loadPluginLibrary", + "mj_local2Global", + "mj_makeConstraint", + "mj_makeM", + "mj_mulJacTVec", + "mj_mulJacVec", + "mj_mulM", + "mj_mulM2", + "mj_multiRay", + "mj_name2id", + "mj_normalizeQuat", + "mj_objectAcceleration", + "mj_objectVelocity", + "mj_passive", + "mj_printData", + "mj_printFormattedData", + "mj_printFormattedModel", + "mj_printModel", + "mj_printSchema", + "mj_projectConstraint", + "mj_ray", + "mj_rayHfield", + "mj_rayMesh", + "mj_referenceConstraint", + "mj_resetCallbacks", + "mj_resetData", + "mj_resetDataDebug", + "mj_resetDataKeyframe", + "mj_rne", + "mj_rnePostConstraint", + "mj_saveLastXML", + "mj_saveModel", + "mj_sensorAcc", + "mj_sensorPos", + "mj_sensorVel", + "mj_setConst", + "mj_setKeyframe", + "mj_setLengthRange", + "mj_setState", + "mj_setTotalmass", + "mj_sizeModel", + "mj_solveM", + "mj_solveM2", + "mj_stateSize", + "mj_step", + "mj_step1", + "mj_step2", + "mj_subtreeVel", + "mj_tendon", + "mj_transmission", + "mj_version", + "mj_versionString", + "mjd_inverseFD", + "mjd_quatIntegrate", + "mjd_subQuat", + "mjd_transitionFD", + "mjr_addAux", + "mjr_blitAux", + "mjr_blitBuffer", + "mjr_changeFont", + "mjr_drawPixels", + "mjr_figure", + "mjr_findRect", + "mjr_finish", + "mjr_getError", + "mjr_label", + "mjr_maxViewport", + "mjr_overlay", + "mjr_readPixels", + "mjr_rectangle", + "mjr_render", + "mjr_resizeOffscreen", + "mjr_restoreBuffer", + "mjr_setAux", + "mjr_setBuffer", + "mjr_text", + "mjr_uploadHField", + "mjr_uploadMesh", + "mjr_uploadTexture", + "mjtAlignFree", + "mjtBias", + "mjtBuiltin", + "mjtButton", + "mjtCamLight", + "mjtCamera", + "mjtCatBit", + "mjtColorSpace", + "mjtConDataField", + "mjtCone", + "mjtConstraint", + "mjtConstraintState", + "mjtDataType", + "mjtDepthMap", + "mjtDisableBit", + "mjtDyn", + "mjtEnableBit", + "mjtEq", + "mjtEvent", + "mjtFlexSelf", + "mjtFont", + "mjtFontScale", + "mjtFrame", + "mjtFramebuffer", + "mjtGain", + "mjtGeom", + "mjtGeomInertia", + "mjtGridPos", + "mjtInertiaFromGeom", + "mjtIntegrator", + "mjtItem", + "mjtJacobian", + "mjtJoint", + "mjtLRMode", + "mjtLabel", + "mjtLightType", + "mjtLimited", + "mjtMark", + "mjtMeshBuiltin", + "mjtMeshInertia", + "mjtMouse", + "mjtObj", + "mjtOrientation", + "mjtPertBit", + "mjtPluginCapabilityBit", + "mjtRndFlag", + "mjtSDFType", + "mjtSameFrame", + "mjtSection", + "mjtSensor", + "mjtSolver", + "mjtStage", + "mjtState", + "mjtStereo", + "mjtTaskStatus", + "mjtTexture", + "mjtTextureRole", + "mjtTimer", + "mjtTrn", + "mjtVisFlag", + "mjtWarning", + "mjtWrap", + "mju_Halton", + "mju_L1", + "mju_add", + "mju_add3", + "mju_addScl", + "mju_addScl3", + "mju_addTo", + "mju_addTo3", + "mju_addToScl", + "mju_addToScl3", + "mju_axisAngle2Quat", + "mju_band2Dense", + "mju_bandDiag", + "mju_bandMulMatVec", + "mju_boxQP", + "mju_cholFactor", + "mju_cholFactorBand", + "mju_cholSolve", + "mju_cholSolveBand", + "mju_cholUpdate", + "mju_clip", + "mju_copy", + "mju_copy3", + "mju_copy4", + "mju_cross", + "mju_d2n", + "mju_decodePyramid", + "mju_dense2Band", + "mju_dense2sparse", + "mju_derivQuat", + "mju_dist3", + "mju_dot", + "mju_dot3", + "mju_eig3", + "mju_encodePyramid", + "mju_euler2Quat", + "mju_eye", + "mju_f2n", + "mju_fill", + "mju_insertionSort", + "mju_insertionSortInt", + "mju_isBad", + "mju_isZero", + "mju_mat2Quat", + "mju_mat2Rot", + "mju_max", + "mju_min", + "mju_mulMatMat", + "mju_mulMatMatT", + "mju_mulMatTMat", + "mju_mulMatTVec", + "mju_mulMatTVec3", + "mju_mulMatVec", + "mju_mulMatVec3", + "mju_mulPose", + "mju_mulQuat", + "mju_mulQuatAxis", + "mju_mulVecMatVec", + "mju_muscleBias", + "mju_muscleDynamics", + "mju_muscleGain", + "mju_n2d", + "mju_n2f", + "mju_negPose", + "mju_negQuat", + "mju_norm", + "mju_norm3", + "mju_normalize", + "mju_normalize3", + "mju_normalize4", + "mju_printMat", + "mju_printMatSparse", + "mju_quat2Mat", + "mju_quat2Vel", + "mju_quatIntegrate", + "mju_quatZ2Vec", + "mju_rayFlex", + "mju_rayGeom", + "mju_raySkin", + "mju_rotVecQuat", + "mju_round", + "mju_scl", + "mju_scl3", + "mju_sigmoid", + "mju_sign", + "mju_sparse2dense", + "mju_springDamper", + "mju_sqrMatTD", + "mju_standardNormal", + "mju_str2Type", + "mju_sub", + "mju_sub3", + "mju_subFrom", + "mju_subFrom3", + "mju_subQuat", + "mju_sum", + "mju_symmetrize", + "mju_transformSpatial", + "mju_transpose", + "mju_trnVecPose", + "mju_type2Str", + "mju_unit4", + "mju_warningText", + "mju_writeLog", + "mju_writeNumBytes", + "mju_zero", + "mju_zero3", + "mju_zero4", + "mjv_addGeoms", + "mjv_alignToCamera", + "mjv_applyPerturbForce", + "mjv_applyPerturbPose", + "mjv_averageCamera", + "mjv_cameraInModel", + "mjv_cameraInRoom", + "mjv_connector", + "mjv_defaultCamera", + "mjv_defaultFigure", + "mjv_defaultFreeCamera", + "mjv_defaultOption", + "mjv_defaultPerturb", + "mjv_frustumHeight", + "mjv_initGeom", + "mjv_initPerturb", + "mjv_makeLights", + "mjv_model2room", + "mjv_moveCamera", + "mjv_moveModel", + "mjv_movePerturb", + "mjv_room2model", + "mjv_select", + "mjv_updateCamera", + "mjv_updateScene", + "mjv_updateSkin", + "os", + "platform", + "renderer", + "set_mjcb_act_bias", + "set_mjcb_act_dyn", + "set_mjcb_act_gain", + "set_mjcb_contactfilter", + "set_mjcb_control", + "set_mjcb_passive", + "set_mjcb_sensor", + "set_mjcb_time", + "set_mju_user_free", + "set_mju_user_malloc", + "set_mju_user_warning", + "subprocess", + "to_zip", + "warnings", + "zipfile", +] + +class FatalError(Exception): + pass + +class UnexpectedError(Exception): + pass + +class _MjBindData: + def __getattr__(self, key: str): ... + def __init__(self, elements: typing.Sequence[typing.Any]): ... + +class _MjBindModel: + def __getattr__(self, key: str): ... + def __init__(self, elements: typing.Sequence[typing.Any]): ... + +def _bind_data( + data: _structs.MjData, + specs: typing.Union[ + typing.Sequence[ + typing.Union[ + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ] + ], + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ], +): + """ + Bind a Mujoco spec to a mjData. + + Args: + data: The mjData to bind to. + specs: The mjSpec elements to use for binding, can be a single element or a + sequence. + Returns: + A MjDataGroupedViews object or a list of the same type. + """ + +def _bind_model( + model: _structs.MjModel, + specs: typing.Union[ + typing.Sequence[ + typing.Union[ + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ] + ], + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ], +): + """ + Bind a Mujoco spec to a mjModel. + + Args: + model: The mjModel to bind to. + specs: The mjSpec elements to use for binding, can be a single element or a + sequence. + Returns: + A MjModelGroupedViews object or a list of the same type. + """ + +def _load_all_bundled_plugins(): ... +def from_zip(file: typing.Union[str, typing.IO[bytes]]) -> _specs.MjSpec: + """ + Reads a zip file and returns an MjSpec. + + Args: + file: The path to the file to read from or the file object to read from. + Returns: + An MjSpec object. + """ + +def to_zip(spec: _specs.MjSpec, file: typing.Union[str, typing.IO[bytes]]) -> None: + """ + Converts an MjSpec to a zip file. + + Args: + spec: The mjSpec to save to a file. + file: The path to the file to save to or the file object to write to. + """ + +HEADERS_DIR: str = ( + "/home/brent/mjlab/.venv/lib/python3.13/site-packages/mujoco/include/mujoco" +) +MjStruct: typing._UnionGenericAlias # value = typing.Union[mujoco._specs.MjsBody, mujoco._specs.MjsFrame, mujoco._specs.MjsGeom, mujoco._specs.MjsJoint, mujoco._specs.MjsLight, mujoco._specs.MjsMaterial, mujoco._specs.MjsSite, mujoco._specs.MjsMesh, mujoco._specs.MjsSkin, mujoco._specs.MjsTexture, mujoco._specs.MjsText, mujoco._specs.MjsTuple, mujoco._specs.MjsCamera, mujoco._specs.MjsFlex, mujoco._specs.MjsHField, mujoco._specs.MjsKey, mujoco._specs.MjsNumeric, mujoco._specs.MjsPair, mujoco._specs.MjsExclude, mujoco._specs.MjsEquality, mujoco._specs.MjsTendon, mujoco._specs.MjsSensor, mujoco._specs.MjsActuator, mujoco._specs.MjsPlugin] +PLUGINS_DIR: str = "/home/brent/mjlab/.venv/lib/python3.13/site-packages/mujoco/plugin" +PLUGIN_HANDLES: list # value = [, , , ] +_SYSTEM: str = "Linux" +__version__: str = "3.3.6" +mjDISABLESTRING: tuple = ( + "Constraint", + "Equality", + "Frictionloss", + "Limit", + "Contact", + "Passive", + "Gravity", + "Clampctrl", + "Warmstart", + "Filterparent", + "Actuation", + "Refsafe", + "Sensor", + "Midphase", + "Eulerdamp", + "AutoReset", + "NativeCCD", +) +mjENABLESTRING: tuple = ( + "Override", + "Energy", + "Fwdinv", + "InvDiscrete", + "MultiCCD", + "Island", +) +mjFRAMESTRING: tuple = ( + "None", + "Body", + "Geom", + "Site", + "Camera", + "Light", + "Contact", + "World", +) +mjLABELSTRING: tuple = ( + "None", + "Body", + "Joint", + "Geom", + "Site", + "Camera", + "Light", + "Tendon", + "Actuator", + "Constraint", + "Flex", + "Skin", + "Selection", + "SelPoint", + "Contact", + "ContactForce", + "Island", +) +mjMAXCONPAIR: int = 50 +mjMAXIMP: float = 0.9999 +mjMAXLIGHT: int = 100 +mjMAXLINE: int = 100 +mjMAXLINEPNT: int = 1001 +mjMAXOVERLAY: int = 500 +mjMAXPLANEGRID: int = 200 +mjMAXVAL: float = 10000000000.0 +mjMINIMP: float = 0.0001 +mjMINMU: float = 1e-05 +mjMINVAL: float = 1e-15 +mjNBIAS: int = 10 +mjNDYN: int = 10 +mjNEQDATA: int = 11 +mjNGAIN: int = 10 +mjNGROUP: int = 6 +mjNIMP: int = 5 +mjNREF: int = 2 +mjNSOLVER: int = 200 +mjPI: float = 3.141592653589793 +mjRNDSTRING: tuple = ( + ("Shadow", "1", "S"), + ("Wireframe", "0", "W"), + ("Reflection", "1", "R"), + ("Additive", "0", "L"), + ("Skybox", "1", "K"), + ("Fog", "0", "G"), + ("Haze", "1", "/"), + ("Segment", "0", ","), + ("Id Color", "0", ""), + ("Cull Face", "1", ""), +) +mjTIMERSTRING: tuple = ( + "step", + "forward", + "inverse", + "position", + "velocity", + "actuation", + "constraint", + "advance", + "pos_kinematics", + "pos_inertia", + "pos_collision", + "pos_make", + "pos_project", + "col_broadphase", + "col_narrowphase", +) +mjVERSION_HEADER: int = 336 +mjVISSTRING: tuple = ( + ("Convex Hull", "0", "H"), + ("Texture", "1", "X"), + ("Joint", "0", "J"), + ("Camera", "0", "Q"), + ("Actuator", "0", "U"), + ("Activation", "0", ","), + ("Light", "0", "Z"), + ("Tendon", "1", "V"), + ("Range Finder", "1", "Y"), + ("Equality", "0", "E"), + ("Inertia", "0", "I"), + ("Scale Inertia", "0", "'"), + ("Perturb Force", "0", "B"), + ("Perturb Object", "1", "O"), + ("Contact Point", "0", "C"), + ("Island", "0", "N"), + ("Contact Force", "0", "F"), + ("Contact Split", "0", "P"), + ("Transparent", "0", "T"), + ("Auto Connect", "0", "A"), + ("Center of Mass", "0", "M"), + ("Select Point", "0", ""), + ("Static Body", "1", "D"), + ("Skin", "1", ";"), + ("Flex Vert", "0", ""), + ("Flex Edge", "1", ""), + ("Flex Face", "0", ""), + ("Flex Skin", "1", ""), + ("Body Tree", "0", "`"), + ("Mesh Tree", "0", "\\"), + ("SDF iters", "0", ""), +) diff --git a/typings/mujoco/_callbacks.pyi b/typings/mujoco/_callbacks.pyi new file mode 100644 index 000000000..306b101a0 --- /dev/null +++ b/typings/mujoco/_callbacks.pyi @@ -0,0 +1,50 @@ +from __future__ import annotations +import typing + +__all__: list[str] = [ + "get_mjcb_act_bias", + "get_mjcb_act_dyn", + "get_mjcb_act_gain", + "get_mjcb_contactfilter", + "get_mjcb_control", + "get_mjcb_passive", + "get_mjcb_sensor", + "get_mjcb_time", + "get_mju_user_free", + "get_mju_user_malloc", + "get_mju_user_warning", + "set_mjcb_act_bias", + "set_mjcb_act_dyn", + "set_mjcb_act_gain", + "set_mjcb_contactfilter", + "set_mjcb_control", + "set_mjcb_passive", + "set_mjcb_sensor", + "set_mjcb_time", + "set_mju_user_free", + "set_mju_user_malloc", + "set_mju_user_warning", +] + +def get_mjcb_act_bias() -> typing.Any: ... +def get_mjcb_act_dyn() -> typing.Any: ... +def get_mjcb_act_gain() -> typing.Any: ... +def get_mjcb_contactfilter() -> typing.Any: ... +def get_mjcb_control() -> typing.Any: ... +def get_mjcb_passive() -> typing.Any: ... +def get_mjcb_sensor() -> typing.Any: ... +def get_mjcb_time() -> typing.Any: ... +def get_mju_user_free() -> typing.Any: ... +def get_mju_user_malloc() -> typing.Any: ... +def get_mju_user_warning() -> typing.Any: ... +def set_mjcb_act_bias(arg0: typing.Any) -> None: ... +def set_mjcb_act_dyn(arg0: typing.Any) -> None: ... +def set_mjcb_act_gain(arg0: typing.Any) -> None: ... +def set_mjcb_contactfilter(arg0: typing.Any) -> None: ... +def set_mjcb_control(arg0: typing.Any) -> None: ... +def set_mjcb_passive(arg0: typing.Any) -> None: ... +def set_mjcb_sensor(arg0: typing.Any) -> None: ... +def set_mjcb_time(arg0: typing.Any) -> None: ... +def set_mju_user_free(arg0: typing.Any) -> None: ... +def set_mju_user_malloc(arg0: typing.Any) -> None: ... +def set_mju_user_warning(arg0: typing.Any) -> None: ... diff --git a/typings/mujoco/_constants.pyi b/typings/mujoco/_constants.pyi new file mode 100644 index 000000000..3e184d890 --- /dev/null +++ b/typings/mujoco/_constants.pyi @@ -0,0 +1,171 @@ +from __future__ import annotations + +__all__: list[str] = [ + "mjDISABLESTRING", + "mjENABLESTRING", + "mjFRAMESTRING", + "mjLABELSTRING", + "mjMAXCONPAIR", + "mjMAXIMP", + "mjMAXLIGHT", + "mjMAXLINE", + "mjMAXLINEPNT", + "mjMAXOVERLAY", + "mjMAXPLANEGRID", + "mjMAXVAL", + "mjMINIMP", + "mjMINMU", + "mjMINVAL", + "mjNBIAS", + "mjNDYN", + "mjNEQDATA", + "mjNGAIN", + "mjNGROUP", + "mjNIMP", + "mjNREF", + "mjNSOLVER", + "mjPI", + "mjRNDSTRING", + "mjTIMERSTRING", + "mjVERSION_HEADER", + "mjVISSTRING", +] +mjDISABLESTRING: tuple = ( + "Constraint", + "Equality", + "Frictionloss", + "Limit", + "Contact", + "Passive", + "Gravity", + "Clampctrl", + "Warmstart", + "Filterparent", + "Actuation", + "Refsafe", + "Sensor", + "Midphase", + "Eulerdamp", + "AutoReset", + "NativeCCD", +) +mjENABLESTRING: tuple = ( + "Override", + "Energy", + "Fwdinv", + "InvDiscrete", + "MultiCCD", + "Island", +) +mjFRAMESTRING: tuple = ( + "None", + "Body", + "Geom", + "Site", + "Camera", + "Light", + "Contact", + "World", +) +mjLABELSTRING: tuple = ( + "None", + "Body", + "Joint", + "Geom", + "Site", + "Camera", + "Light", + "Tendon", + "Actuator", + "Constraint", + "Flex", + "Skin", + "Selection", + "SelPoint", + "Contact", + "ContactForce", + "Island", +) +mjMAXCONPAIR: int = 50 +mjMAXIMP: float = 0.9999 +mjMAXLIGHT: int = 100 +mjMAXLINE: int = 100 +mjMAXLINEPNT: int = 1001 +mjMAXOVERLAY: int = 500 +mjMAXPLANEGRID: int = 200 +mjMAXVAL: float = 10000000000.0 +mjMINIMP: float = 0.0001 +mjMINMU: float = 1e-05 +mjMINVAL: float = 1e-15 +mjNBIAS: int = 10 +mjNDYN: int = 10 +mjNEQDATA: int = 11 +mjNGAIN: int = 10 +mjNGROUP: int = 6 +mjNIMP: int = 5 +mjNREF: int = 2 +mjNSOLVER: int = 200 +mjPI: float = 3.141592653589793 +mjRNDSTRING: tuple = ( + ("Shadow", "1", "S"), + ("Wireframe", "0", "W"), + ("Reflection", "1", "R"), + ("Additive", "0", "L"), + ("Skybox", "1", "K"), + ("Fog", "0", "G"), + ("Haze", "1", "/"), + ("Segment", "0", ","), + ("Id Color", "0", ""), + ("Cull Face", "1", ""), +) +mjTIMERSTRING: tuple = ( + "step", + "forward", + "inverse", + "position", + "velocity", + "actuation", + "constraint", + "advance", + "pos_kinematics", + "pos_inertia", + "pos_collision", + "pos_make", + "pos_project", + "col_broadphase", + "col_narrowphase", +) +mjVERSION_HEADER: int = 336 +mjVISSTRING: tuple = ( + ("Convex Hull", "0", "H"), + ("Texture", "1", "X"), + ("Joint", "0", "J"), + ("Camera", "0", "Q"), + ("Actuator", "0", "U"), + ("Activation", "0", ","), + ("Light", "0", "Z"), + ("Tendon", "1", "V"), + ("Range Finder", "1", "Y"), + ("Equality", "0", "E"), + ("Inertia", "0", "I"), + ("Scale Inertia", "0", "'"), + ("Perturb Force", "0", "B"), + ("Perturb Object", "1", "O"), + ("Contact Point", "0", "C"), + ("Island", "0", "N"), + ("Contact Force", "0", "F"), + ("Contact Split", "0", "P"), + ("Transparent", "0", "T"), + ("Auto Connect", "0", "A"), + ("Center of Mass", "0", "M"), + ("Select Point", "0", ""), + ("Static Body", "1", "D"), + ("Skin", "1", ";"), + ("Flex Vert", "0", ""), + ("Flex Edge", "1", ""), + ("Flex Face", "0", ""), + ("Flex Skin", "1", ""), + ("Body Tree", "0", "`"), + ("Mesh Tree", "0", "\\"), + ("SDF iters", "0", ""), +) diff --git a/typings/mujoco/_enums.pyi b/typings/mujoco/_enums.pyi new file mode 100644 index 000000000..748182ed8 --- /dev/null +++ b/typings/mujoco/_enums.pyi @@ -0,0 +1,6695 @@ +from __future__ import annotations +import typing + +__all__: list[str] = [ + "mjtAlignFree", + "mjtBias", + "mjtBuiltin", + "mjtButton", + "mjtCamLight", + "mjtCamera", + "mjtCatBit", + "mjtColorSpace", + "mjtConDataField", + "mjtCone", + "mjtConstraint", + "mjtConstraintState", + "mjtDataType", + "mjtDepthMap", + "mjtDisableBit", + "mjtDyn", + "mjtEnableBit", + "mjtEq", + "mjtEvent", + "mjtFlexSelf", + "mjtFont", + "mjtFontScale", + "mjtFrame", + "mjtFramebuffer", + "mjtGain", + "mjtGeom", + "mjtGeomInertia", + "mjtGridPos", + "mjtInertiaFromGeom", + "mjtIntegrator", + "mjtItem", + "mjtJacobian", + "mjtJoint", + "mjtLRMode", + "mjtLabel", + "mjtLightType", + "mjtLimited", + "mjtMark", + "mjtMeshBuiltin", + "mjtMeshInertia", + "mjtMouse", + "mjtObj", + "mjtOrientation", + "mjtPertBit", + "mjtPluginCapabilityBit", + "mjtRndFlag", + "mjtSDFType", + "mjtSameFrame", + "mjtSection", + "mjtSensor", + "mjtSolver", + "mjtStage", + "mjtState", + "mjtStereo", + "mjtTaskStatus", + "mjtTexture", + "mjtTextureRole", + "mjtTimer", + "mjtTrn", + "mjtVisFlag", + "mjtWarning", + "mjtWrap", +] + +class mjtAlignFree: + """ + Members: + + mjALIGNFREE_FALSE + + mjALIGNFREE_TRUE + + mjALIGNFREE_AUTO + """ + + __members__: typing.ClassVar[ + dict[str, mjtAlignFree] + ] # value = {'mjALIGNFREE_FALSE': , 'mjALIGNFREE_TRUE': , 'mjALIGNFREE_AUTO': } + mjALIGNFREE_AUTO: typing.ClassVar[ + mjtAlignFree + ] # value = + mjALIGNFREE_FALSE: typing.ClassVar[ + mjtAlignFree + ] # value = + mjALIGNFREE_TRUE: typing.ClassVar[ + mjtAlignFree + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtBias: + """ + Members: + + mjBIAS_NONE + + mjBIAS_AFFINE + + mjBIAS_MUSCLE + + mjBIAS_USER + """ + + __members__: typing.ClassVar[ + dict[str, mjtBias] + ] # value = {'mjBIAS_NONE': , 'mjBIAS_AFFINE': , 'mjBIAS_MUSCLE': , 'mjBIAS_USER': } + mjBIAS_AFFINE: typing.ClassVar[mjtBias] # value = + mjBIAS_MUSCLE: typing.ClassVar[mjtBias] # value = + mjBIAS_NONE: typing.ClassVar[mjtBias] # value = + mjBIAS_USER: typing.ClassVar[mjtBias] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtBuiltin: + """ + Members: + + mjBUILTIN_NONE + + mjBUILTIN_GRADIENT + + mjBUILTIN_CHECKER + + mjBUILTIN_FLAT + """ + + __members__: typing.ClassVar[ + dict[str, mjtBuiltin] + ] # value = {'mjBUILTIN_NONE': , 'mjBUILTIN_GRADIENT': , 'mjBUILTIN_CHECKER': , 'mjBUILTIN_FLAT': } + mjBUILTIN_CHECKER: typing.ClassVar[ + mjtBuiltin + ] # value = + mjBUILTIN_FLAT: typing.ClassVar[mjtBuiltin] # value = + mjBUILTIN_GRADIENT: typing.ClassVar[ + mjtBuiltin + ] # value = + mjBUILTIN_NONE: typing.ClassVar[mjtBuiltin] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtButton: + """ + Members: + + mjBUTTON_NONE + + mjBUTTON_LEFT + + mjBUTTON_RIGHT + + mjBUTTON_MIDDLE + """ + + __members__: typing.ClassVar[ + dict[str, mjtButton] + ] # value = {'mjBUTTON_NONE': , 'mjBUTTON_LEFT': , 'mjBUTTON_RIGHT': , 'mjBUTTON_MIDDLE': } + mjBUTTON_LEFT: typing.ClassVar[mjtButton] # value = + mjBUTTON_MIDDLE: typing.ClassVar[mjtButton] # value = + mjBUTTON_NONE: typing.ClassVar[mjtButton] # value = + mjBUTTON_RIGHT: typing.ClassVar[mjtButton] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtCamLight: + """ + Members: + + mjCAMLIGHT_FIXED + + mjCAMLIGHT_TRACK + + mjCAMLIGHT_TRACKCOM + + mjCAMLIGHT_TARGETBODY + + mjCAMLIGHT_TARGETBODYCOM + """ + + __members__: typing.ClassVar[ + dict[str, mjtCamLight] + ] # value = {'mjCAMLIGHT_FIXED': , 'mjCAMLIGHT_TRACK': , 'mjCAMLIGHT_TRACKCOM': , 'mjCAMLIGHT_TARGETBODY': , 'mjCAMLIGHT_TARGETBODYCOM': } + mjCAMLIGHT_FIXED: typing.ClassVar[ + mjtCamLight + ] # value = + mjCAMLIGHT_TARGETBODY: typing.ClassVar[ + mjtCamLight + ] # value = + mjCAMLIGHT_TARGETBODYCOM: typing.ClassVar[ + mjtCamLight + ] # value = + mjCAMLIGHT_TRACK: typing.ClassVar[ + mjtCamLight + ] # value = + mjCAMLIGHT_TRACKCOM: typing.ClassVar[ + mjtCamLight + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtCamera: + """ + Members: + + mjCAMERA_FREE + + mjCAMERA_TRACKING + + mjCAMERA_FIXED + + mjCAMERA_USER + """ + + __members__: typing.ClassVar[ + dict[str, mjtCamera] + ] # value = {'mjCAMERA_FREE': , 'mjCAMERA_TRACKING': , 'mjCAMERA_FIXED': , 'mjCAMERA_USER': } + mjCAMERA_FIXED: typing.ClassVar[mjtCamera] # value = + mjCAMERA_FREE: typing.ClassVar[mjtCamera] # value = + mjCAMERA_TRACKING: typing.ClassVar[ + mjtCamera + ] # value = + mjCAMERA_USER: typing.ClassVar[mjtCamera] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtCatBit: + """ + Members: + + mjCAT_STATIC + + mjCAT_DYNAMIC + + mjCAT_DECOR + + mjCAT_ALL + """ + + __members__: typing.ClassVar[ + dict[str, mjtCatBit] + ] # value = {'mjCAT_STATIC': , 'mjCAT_DYNAMIC': , 'mjCAT_DECOR': , 'mjCAT_ALL': } + mjCAT_ALL: typing.ClassVar[mjtCatBit] # value = + mjCAT_DECOR: typing.ClassVar[mjtCatBit] # value = + mjCAT_DYNAMIC: typing.ClassVar[mjtCatBit] # value = + mjCAT_STATIC: typing.ClassVar[mjtCatBit] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtColorSpace: + """ + Members: + + mjCOLORSPACE_AUTO + + mjCOLORSPACE_LINEAR + + mjCOLORSPACE_SRGB + """ + + __members__: typing.ClassVar[ + dict[str, mjtColorSpace] + ] # value = {'mjCOLORSPACE_AUTO': , 'mjCOLORSPACE_LINEAR': , 'mjCOLORSPACE_SRGB': } + mjCOLORSPACE_AUTO: typing.ClassVar[ + mjtColorSpace + ] # value = + mjCOLORSPACE_LINEAR: typing.ClassVar[ + mjtColorSpace + ] # value = + mjCOLORSPACE_SRGB: typing.ClassVar[ + mjtColorSpace + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtConDataField: + """ + Members: + + mjCONDATA_FOUND + + mjCONDATA_FORCE + + mjCONDATA_TORQUE + + mjCONDATA_DIST + + mjCONDATA_POS + + mjCONDATA_NORMAL + + mjCONDATA_TANGENT + + mjNCONDATA + """ + + __members__: typing.ClassVar[ + dict[str, mjtConDataField] + ] # value = {'mjCONDATA_FOUND': , 'mjCONDATA_FORCE': , 'mjCONDATA_TORQUE': , 'mjCONDATA_DIST': , 'mjCONDATA_POS': , 'mjCONDATA_NORMAL': , 'mjCONDATA_TANGENT': , 'mjNCONDATA': } + mjCONDATA_DIST: typing.ClassVar[ + mjtConDataField + ] # value = + mjCONDATA_FORCE: typing.ClassVar[ + mjtConDataField + ] # value = + mjCONDATA_FOUND: typing.ClassVar[ + mjtConDataField + ] # value = + mjCONDATA_NORMAL: typing.ClassVar[ + mjtConDataField + ] # value = + mjCONDATA_POS: typing.ClassVar[ + mjtConDataField + ] # value = + mjCONDATA_TANGENT: typing.ClassVar[ + mjtConDataField + ] # value = + mjCONDATA_TORQUE: typing.ClassVar[ + mjtConDataField + ] # value = + mjNCONDATA: typing.ClassVar[ + mjtConDataField + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtCone: + """ + Members: + + mjCONE_PYRAMIDAL + + mjCONE_ELLIPTIC + """ + + __members__: typing.ClassVar[ + dict[str, mjtCone] + ] # value = {'mjCONE_PYRAMIDAL': , 'mjCONE_ELLIPTIC': } + mjCONE_ELLIPTIC: typing.ClassVar[mjtCone] # value = + mjCONE_PYRAMIDAL: typing.ClassVar[mjtCone] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtConstraint: + """ + Members: + + mjCNSTR_EQUALITY + + mjCNSTR_FRICTION_DOF + + mjCNSTR_FRICTION_TENDON + + mjCNSTR_LIMIT_JOINT + + mjCNSTR_LIMIT_TENDON + + mjCNSTR_CONTACT_FRICTIONLESS + + mjCNSTR_CONTACT_PYRAMIDAL + + mjCNSTR_CONTACT_ELLIPTIC + """ + + __members__: typing.ClassVar[ + dict[str, mjtConstraint] + ] # value = {'mjCNSTR_EQUALITY': , 'mjCNSTR_FRICTION_DOF': , 'mjCNSTR_FRICTION_TENDON': , 'mjCNSTR_LIMIT_JOINT': , 'mjCNSTR_LIMIT_TENDON': , 'mjCNSTR_CONTACT_FRICTIONLESS': , 'mjCNSTR_CONTACT_PYRAMIDAL': , 'mjCNSTR_CONTACT_ELLIPTIC': } + mjCNSTR_CONTACT_ELLIPTIC: typing.ClassVar[ + mjtConstraint + ] # value = + mjCNSTR_CONTACT_FRICTIONLESS: typing.ClassVar[ + mjtConstraint + ] # value = + mjCNSTR_CONTACT_PYRAMIDAL: typing.ClassVar[ + mjtConstraint + ] # value = + mjCNSTR_EQUALITY: typing.ClassVar[ + mjtConstraint + ] # value = + mjCNSTR_FRICTION_DOF: typing.ClassVar[ + mjtConstraint + ] # value = + mjCNSTR_FRICTION_TENDON: typing.ClassVar[ + mjtConstraint + ] # value = + mjCNSTR_LIMIT_JOINT: typing.ClassVar[ + mjtConstraint + ] # value = + mjCNSTR_LIMIT_TENDON: typing.ClassVar[ + mjtConstraint + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtConstraintState: + """ + Members: + + mjCNSTRSTATE_SATISFIED + + mjCNSTRSTATE_QUADRATIC + + mjCNSTRSTATE_LINEARNEG + + mjCNSTRSTATE_LINEARPOS + + mjCNSTRSTATE_CONE + """ + + __members__: typing.ClassVar[ + dict[str, mjtConstraintState] + ] # value = {'mjCNSTRSTATE_SATISFIED': , 'mjCNSTRSTATE_QUADRATIC': , 'mjCNSTRSTATE_LINEARNEG': , 'mjCNSTRSTATE_LINEARPOS': , 'mjCNSTRSTATE_CONE': } + mjCNSTRSTATE_CONE: typing.ClassVar[ + mjtConstraintState + ] # value = + mjCNSTRSTATE_LINEARNEG: typing.ClassVar[ + mjtConstraintState + ] # value = + mjCNSTRSTATE_LINEARPOS: typing.ClassVar[ + mjtConstraintState + ] # value = + mjCNSTRSTATE_QUADRATIC: typing.ClassVar[ + mjtConstraintState + ] # value = + mjCNSTRSTATE_SATISFIED: typing.ClassVar[ + mjtConstraintState + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtDataType: + """ + Members: + + mjDATATYPE_REAL + + mjDATATYPE_POSITIVE + + mjDATATYPE_AXIS + + mjDATATYPE_QUATERNION + """ + + __members__: typing.ClassVar[ + dict[str, mjtDataType] + ] # value = {'mjDATATYPE_REAL': , 'mjDATATYPE_POSITIVE': , 'mjDATATYPE_AXIS': , 'mjDATATYPE_QUATERNION': } + mjDATATYPE_AXIS: typing.ClassVar[ + mjtDataType + ] # value = + mjDATATYPE_POSITIVE: typing.ClassVar[ + mjtDataType + ] # value = + mjDATATYPE_QUATERNION: typing.ClassVar[ + mjtDataType + ] # value = + mjDATATYPE_REAL: typing.ClassVar[ + mjtDataType + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtDepthMap: + """ + Members: + + mjDEPTH_ZERONEAR + + mjDEPTH_ZEROFAR + """ + + __members__: typing.ClassVar[ + dict[str, mjtDepthMap] + ] # value = {'mjDEPTH_ZERONEAR': , 'mjDEPTH_ZEROFAR': } + mjDEPTH_ZEROFAR: typing.ClassVar[ + mjtDepthMap + ] # value = + mjDEPTH_ZERONEAR: typing.ClassVar[ + mjtDepthMap + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtDisableBit: + """ + Members: + + mjDSBL_CONSTRAINT + + mjDSBL_EQUALITY + + mjDSBL_FRICTIONLOSS + + mjDSBL_LIMIT + + mjDSBL_CONTACT + + mjDSBL_PASSIVE + + mjDSBL_GRAVITY + + mjDSBL_CLAMPCTRL + + mjDSBL_WARMSTART + + mjDSBL_FILTERPARENT + + mjDSBL_ACTUATION + + mjDSBL_REFSAFE + + mjDSBL_SENSOR + + mjDSBL_MIDPHASE + + mjDSBL_EULERDAMP + + mjDSBL_AUTORESET + + mjDSBL_NATIVECCD + + mjNDISABLE + """ + + __members__: typing.ClassVar[ + dict[str, mjtDisableBit] + ] # value = {'mjDSBL_CONSTRAINT': , 'mjDSBL_EQUALITY': , 'mjDSBL_FRICTIONLOSS': , 'mjDSBL_LIMIT': , 'mjDSBL_CONTACT': , 'mjDSBL_PASSIVE': , 'mjDSBL_GRAVITY': , 'mjDSBL_CLAMPCTRL': , 'mjDSBL_WARMSTART': , 'mjDSBL_FILTERPARENT': , 'mjDSBL_ACTUATION': , 'mjDSBL_REFSAFE': , 'mjDSBL_SENSOR': , 'mjDSBL_MIDPHASE': , 'mjDSBL_EULERDAMP': , 'mjDSBL_AUTORESET': , 'mjDSBL_NATIVECCD': , 'mjNDISABLE': } + mjDSBL_ACTUATION: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_AUTORESET: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_CLAMPCTRL: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_CONSTRAINT: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_CONTACT: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_EQUALITY: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_EULERDAMP: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_FILTERPARENT: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_FRICTIONLOSS: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_GRAVITY: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_LIMIT: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_MIDPHASE: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_NATIVECCD: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_PASSIVE: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_REFSAFE: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_SENSOR: typing.ClassVar[ + mjtDisableBit + ] # value = + mjDSBL_WARMSTART: typing.ClassVar[ + mjtDisableBit + ] # value = + mjNDISABLE: typing.ClassVar[mjtDisableBit] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtDyn: + """ + Members: + + mjDYN_NONE + + mjDYN_INTEGRATOR + + mjDYN_FILTER + + mjDYN_FILTEREXACT + + mjDYN_MUSCLE + + mjDYN_USER + """ + + __members__: typing.ClassVar[ + dict[str, mjtDyn] + ] # value = {'mjDYN_NONE': , 'mjDYN_INTEGRATOR': , 'mjDYN_FILTER': , 'mjDYN_FILTEREXACT': , 'mjDYN_MUSCLE': , 'mjDYN_USER': } + mjDYN_FILTER: typing.ClassVar[mjtDyn] # value = + mjDYN_FILTEREXACT: typing.ClassVar[mjtDyn] # value = + mjDYN_INTEGRATOR: typing.ClassVar[mjtDyn] # value = + mjDYN_MUSCLE: typing.ClassVar[mjtDyn] # value = + mjDYN_NONE: typing.ClassVar[mjtDyn] # value = + mjDYN_USER: typing.ClassVar[mjtDyn] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtEnableBit: + """ + Members: + + mjENBL_OVERRIDE + + mjENBL_ENERGY + + mjENBL_FWDINV + + mjENBL_INVDISCRETE + + mjENBL_MULTICCD + + mjENBL_ISLAND + + mjNENABLE + """ + + __members__: typing.ClassVar[ + dict[str, mjtEnableBit] + ] # value = {'mjENBL_OVERRIDE': , 'mjENBL_ENERGY': , 'mjENBL_FWDINV': , 'mjENBL_INVDISCRETE': , 'mjENBL_MULTICCD': , 'mjENBL_ISLAND': , 'mjNENABLE': } + mjENBL_ENERGY: typing.ClassVar[ + mjtEnableBit + ] # value = + mjENBL_FWDINV: typing.ClassVar[ + mjtEnableBit + ] # value = + mjENBL_INVDISCRETE: typing.ClassVar[ + mjtEnableBit + ] # value = + mjENBL_ISLAND: typing.ClassVar[ + mjtEnableBit + ] # value = + mjENBL_MULTICCD: typing.ClassVar[ + mjtEnableBit + ] # value = + mjENBL_OVERRIDE: typing.ClassVar[ + mjtEnableBit + ] # value = + mjNENABLE: typing.ClassVar[mjtEnableBit] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtEq: + """ + Members: + + mjEQ_CONNECT + + mjEQ_WELD + + mjEQ_JOINT + + mjEQ_TENDON + + mjEQ_FLEX + + mjEQ_DISTANCE + """ + + __members__: typing.ClassVar[ + dict[str, mjtEq] + ] # value = {'mjEQ_CONNECT': , 'mjEQ_WELD': , 'mjEQ_JOINT': , 'mjEQ_TENDON': , 'mjEQ_FLEX': , 'mjEQ_DISTANCE': } + mjEQ_CONNECT: typing.ClassVar[mjtEq] # value = + mjEQ_DISTANCE: typing.ClassVar[mjtEq] # value = + mjEQ_FLEX: typing.ClassVar[mjtEq] # value = + mjEQ_JOINT: typing.ClassVar[mjtEq] # value = + mjEQ_TENDON: typing.ClassVar[mjtEq] # value = + mjEQ_WELD: typing.ClassVar[mjtEq] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtEvent: + """ + Members: + + mjEVENT_NONE + + mjEVENT_MOVE + + mjEVENT_PRESS + + mjEVENT_RELEASE + + mjEVENT_SCROLL + + mjEVENT_KEY + + mjEVENT_RESIZE + + mjEVENT_REDRAW + + mjEVENT_FILESDROP + """ + + __members__: typing.ClassVar[ + dict[str, mjtEvent] + ] # value = {'mjEVENT_NONE': , 'mjEVENT_MOVE': , 'mjEVENT_PRESS': , 'mjEVENT_RELEASE': , 'mjEVENT_SCROLL': , 'mjEVENT_KEY': , 'mjEVENT_RESIZE': , 'mjEVENT_REDRAW': , 'mjEVENT_FILESDROP': } + mjEVENT_FILESDROP: typing.ClassVar[ + mjtEvent + ] # value = + mjEVENT_KEY: typing.ClassVar[mjtEvent] # value = + mjEVENT_MOVE: typing.ClassVar[mjtEvent] # value = + mjEVENT_NONE: typing.ClassVar[mjtEvent] # value = + mjEVENT_PRESS: typing.ClassVar[mjtEvent] # value = + mjEVENT_REDRAW: typing.ClassVar[mjtEvent] # value = + mjEVENT_RELEASE: typing.ClassVar[mjtEvent] # value = + mjEVENT_RESIZE: typing.ClassVar[mjtEvent] # value = + mjEVENT_SCROLL: typing.ClassVar[mjtEvent] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtFlexSelf: + """ + Members: + + mjFLEXSELF_NONE + + mjFLEXSELF_NARROW + + mjFLEXSELF_BVH + + mjFLEXSELF_SAP + + mjFLEXSELF_AUTO + """ + + __members__: typing.ClassVar[ + dict[str, mjtFlexSelf] + ] # value = {'mjFLEXSELF_NONE': , 'mjFLEXSELF_NARROW': , 'mjFLEXSELF_BVH': , 'mjFLEXSELF_SAP': , 'mjFLEXSELF_AUTO': } + mjFLEXSELF_AUTO: typing.ClassVar[ + mjtFlexSelf + ] # value = + mjFLEXSELF_BVH: typing.ClassVar[ + mjtFlexSelf + ] # value = + mjFLEXSELF_NARROW: typing.ClassVar[ + mjtFlexSelf + ] # value = + mjFLEXSELF_NONE: typing.ClassVar[ + mjtFlexSelf + ] # value = + mjFLEXSELF_SAP: typing.ClassVar[ + mjtFlexSelf + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtFont: + """ + Members: + + mjFONT_NORMAL + + mjFONT_SHADOW + + mjFONT_BIG + """ + + __members__: typing.ClassVar[ + dict[str, mjtFont] + ] # value = {'mjFONT_NORMAL': , 'mjFONT_SHADOW': , 'mjFONT_BIG': } + mjFONT_BIG: typing.ClassVar[mjtFont] # value = + mjFONT_NORMAL: typing.ClassVar[mjtFont] # value = + mjFONT_SHADOW: typing.ClassVar[mjtFont] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtFontScale: + """ + Members: + + mjFONTSCALE_50 + + mjFONTSCALE_100 + + mjFONTSCALE_150 + + mjFONTSCALE_200 + + mjFONTSCALE_250 + + mjFONTSCALE_300 + """ + + __members__: typing.ClassVar[ + dict[str, mjtFontScale] + ] # value = {'mjFONTSCALE_50': , 'mjFONTSCALE_100': , 'mjFONTSCALE_150': , 'mjFONTSCALE_200': , 'mjFONTSCALE_250': , 'mjFONTSCALE_300': } + mjFONTSCALE_100: typing.ClassVar[ + mjtFontScale + ] # value = + mjFONTSCALE_150: typing.ClassVar[ + mjtFontScale + ] # value = + mjFONTSCALE_200: typing.ClassVar[ + mjtFontScale + ] # value = + mjFONTSCALE_250: typing.ClassVar[ + mjtFontScale + ] # value = + mjFONTSCALE_300: typing.ClassVar[ + mjtFontScale + ] # value = + mjFONTSCALE_50: typing.ClassVar[ + mjtFontScale + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtFrame: + """ + Members: + + mjFRAME_NONE + + mjFRAME_BODY + + mjFRAME_GEOM + + mjFRAME_SITE + + mjFRAME_CAMERA + + mjFRAME_LIGHT + + mjFRAME_CONTACT + + mjFRAME_WORLD + + mjNFRAME + """ + + __members__: typing.ClassVar[ + dict[str, mjtFrame] + ] # value = {'mjFRAME_NONE': , 'mjFRAME_BODY': , 'mjFRAME_GEOM': , 'mjFRAME_SITE': , 'mjFRAME_CAMERA': , 'mjFRAME_LIGHT': , 'mjFRAME_CONTACT': , 'mjFRAME_WORLD': , 'mjNFRAME': } + mjFRAME_BODY: typing.ClassVar[mjtFrame] # value = + mjFRAME_CAMERA: typing.ClassVar[mjtFrame] # value = + mjFRAME_CONTACT: typing.ClassVar[mjtFrame] # value = + mjFRAME_GEOM: typing.ClassVar[mjtFrame] # value = + mjFRAME_LIGHT: typing.ClassVar[mjtFrame] # value = + mjFRAME_NONE: typing.ClassVar[mjtFrame] # value = + mjFRAME_SITE: typing.ClassVar[mjtFrame] # value = + mjFRAME_WORLD: typing.ClassVar[mjtFrame] # value = + mjNFRAME: typing.ClassVar[mjtFrame] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtFramebuffer: + """ + Members: + + mjFB_WINDOW + + mjFB_OFFSCREEN + """ + + __members__: typing.ClassVar[ + dict[str, mjtFramebuffer] + ] # value = {'mjFB_WINDOW': , 'mjFB_OFFSCREEN': } + mjFB_OFFSCREEN: typing.ClassVar[ + mjtFramebuffer + ] # value = + mjFB_WINDOW: typing.ClassVar[ + mjtFramebuffer + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtGain: + """ + Members: + + mjGAIN_FIXED + + mjGAIN_AFFINE + + mjGAIN_MUSCLE + + mjGAIN_USER + """ + + __members__: typing.ClassVar[ + dict[str, mjtGain] + ] # value = {'mjGAIN_FIXED': , 'mjGAIN_AFFINE': , 'mjGAIN_MUSCLE': , 'mjGAIN_USER': } + mjGAIN_AFFINE: typing.ClassVar[mjtGain] # value = + mjGAIN_FIXED: typing.ClassVar[mjtGain] # value = + mjGAIN_MUSCLE: typing.ClassVar[mjtGain] # value = + mjGAIN_USER: typing.ClassVar[mjtGain] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtGeom: + """ + Members: + + mjGEOM_PLANE + + mjGEOM_HFIELD + + mjGEOM_SPHERE + + mjGEOM_CAPSULE + + mjGEOM_ELLIPSOID + + mjGEOM_CYLINDER + + mjGEOM_BOX + + mjGEOM_MESH + + mjGEOM_SDF + + mjNGEOMTYPES + + mjGEOM_ARROW + + mjGEOM_ARROW1 + + mjGEOM_ARROW2 + + mjGEOM_LINE + + mjGEOM_LINEBOX + + mjGEOM_FLEX + + mjGEOM_SKIN + + mjGEOM_LABEL + + mjGEOM_TRIANGLE + + mjGEOM_NONE + """ + + __members__: typing.ClassVar[ + dict[str, mjtGeom] + ] # value = {'mjGEOM_PLANE': , 'mjGEOM_HFIELD': , 'mjGEOM_SPHERE': , 'mjGEOM_CAPSULE': , 'mjGEOM_ELLIPSOID': , 'mjGEOM_CYLINDER': , 'mjGEOM_BOX': , 'mjGEOM_MESH': , 'mjGEOM_SDF': , 'mjNGEOMTYPES': , 'mjGEOM_ARROW': , 'mjGEOM_ARROW1': , 'mjGEOM_ARROW2': , 'mjGEOM_LINE': , 'mjGEOM_LINEBOX': , 'mjGEOM_FLEX': , 'mjGEOM_SKIN': , 'mjGEOM_LABEL': , 'mjGEOM_TRIANGLE': , 'mjGEOM_NONE': } + mjGEOM_ARROW: typing.ClassVar[mjtGeom] # value = + mjGEOM_ARROW1: typing.ClassVar[mjtGeom] # value = + mjGEOM_ARROW2: typing.ClassVar[mjtGeom] # value = + mjGEOM_BOX: typing.ClassVar[mjtGeom] # value = + mjGEOM_CAPSULE: typing.ClassVar[mjtGeom] # value = + mjGEOM_CYLINDER: typing.ClassVar[mjtGeom] # value = + mjGEOM_ELLIPSOID: typing.ClassVar[mjtGeom] # value = + mjGEOM_FLEX: typing.ClassVar[mjtGeom] # value = + mjGEOM_HFIELD: typing.ClassVar[mjtGeom] # value = + mjGEOM_LABEL: typing.ClassVar[mjtGeom] # value = + mjGEOM_LINE: typing.ClassVar[mjtGeom] # value = + mjGEOM_LINEBOX: typing.ClassVar[mjtGeom] # value = + mjGEOM_MESH: typing.ClassVar[mjtGeom] # value = + mjGEOM_NONE: typing.ClassVar[mjtGeom] # value = + mjGEOM_PLANE: typing.ClassVar[mjtGeom] # value = + mjGEOM_SDF: typing.ClassVar[mjtGeom] # value = + mjGEOM_SKIN: typing.ClassVar[mjtGeom] # value = + mjGEOM_SPHERE: typing.ClassVar[mjtGeom] # value = + mjGEOM_TRIANGLE: typing.ClassVar[mjtGeom] # value = + mjNGEOMTYPES: typing.ClassVar[mjtGeom] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtGeomInertia: + """ + Members: + + mjINERTIA_VOLUME + + mjINERTIA_SHELL + """ + + __members__: typing.ClassVar[ + dict[str, mjtGeomInertia] + ] # value = {'mjINERTIA_VOLUME': , 'mjINERTIA_SHELL': } + mjINERTIA_SHELL: typing.ClassVar[ + mjtGeomInertia + ] # value = + mjINERTIA_VOLUME: typing.ClassVar[ + mjtGeomInertia + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtGridPos: + """ + Members: + + mjGRID_TOPLEFT + + mjGRID_TOPRIGHT + + mjGRID_BOTTOMLEFT + + mjGRID_BOTTOMRIGHT + + mjGRID_TOP + + mjGRID_BOTTOM + + mjGRID_LEFT + + mjGRID_RIGHT + """ + + __members__: typing.ClassVar[ + dict[str, mjtGridPos] + ] # value = {'mjGRID_TOPLEFT': , 'mjGRID_TOPRIGHT': , 'mjGRID_BOTTOMLEFT': , 'mjGRID_BOTTOMRIGHT': , 'mjGRID_TOP': , 'mjGRID_BOTTOM': , 'mjGRID_LEFT': , 'mjGRID_RIGHT': } + mjGRID_BOTTOM: typing.ClassVar[mjtGridPos] # value = + mjGRID_BOTTOMLEFT: typing.ClassVar[ + mjtGridPos + ] # value = + mjGRID_BOTTOMRIGHT: typing.ClassVar[ + mjtGridPos + ] # value = + mjGRID_LEFT: typing.ClassVar[mjtGridPos] # value = + mjGRID_RIGHT: typing.ClassVar[mjtGridPos] # value = + mjGRID_TOP: typing.ClassVar[mjtGridPos] # value = + mjGRID_TOPLEFT: typing.ClassVar[mjtGridPos] # value = + mjGRID_TOPRIGHT: typing.ClassVar[ + mjtGridPos + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtInertiaFromGeom: + """ + Members: + + mjINERTIAFROMGEOM_FALSE + + mjINERTIAFROMGEOM_TRUE + + mjINERTIAFROMGEOM_AUTO + """ + + __members__: typing.ClassVar[ + dict[str, mjtInertiaFromGeom] + ] # value = {'mjINERTIAFROMGEOM_FALSE': , 'mjINERTIAFROMGEOM_TRUE': , 'mjINERTIAFROMGEOM_AUTO': } + mjINERTIAFROMGEOM_AUTO: typing.ClassVar[ + mjtInertiaFromGeom + ] # value = + mjINERTIAFROMGEOM_FALSE: typing.ClassVar[ + mjtInertiaFromGeom + ] # value = + mjINERTIAFROMGEOM_TRUE: typing.ClassVar[ + mjtInertiaFromGeom + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtIntegrator: + """ + Members: + + mjINT_EULER + + mjINT_RK4 + + mjINT_IMPLICIT + + mjINT_IMPLICITFAST + """ + + __members__: typing.ClassVar[ + dict[str, mjtIntegrator] + ] # value = {'mjINT_EULER': , 'mjINT_RK4': , 'mjINT_IMPLICIT': , 'mjINT_IMPLICITFAST': } + mjINT_EULER: typing.ClassVar[mjtIntegrator] # value = + mjINT_IMPLICIT: typing.ClassVar[ + mjtIntegrator + ] # value = + mjINT_IMPLICITFAST: typing.ClassVar[ + mjtIntegrator + ] # value = + mjINT_RK4: typing.ClassVar[mjtIntegrator] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtItem: + """ + Members: + + mjITEM_END + + mjITEM_SECTION + + mjITEM_SEPARATOR + + mjITEM_STATIC + + mjITEM_BUTTON + + mjITEM_CHECKINT + + mjITEM_CHECKBYTE + + mjITEM_RADIO + + mjITEM_RADIOLINE + + mjITEM_SELECT + + mjITEM_SLIDERINT + + mjITEM_SLIDERNUM + + mjITEM_EDITINT + + mjITEM_EDITNUM + + mjITEM_EDITFLOAT + + mjITEM_EDITTXT + + mjNITEM + """ + + __members__: typing.ClassVar[ + dict[str, mjtItem] + ] # value = {'mjITEM_END': , 'mjITEM_SECTION': , 'mjITEM_SEPARATOR': , 'mjITEM_STATIC': , 'mjITEM_BUTTON': , 'mjITEM_CHECKINT': , 'mjITEM_CHECKBYTE': , 'mjITEM_RADIO': , 'mjITEM_RADIOLINE': , 'mjITEM_SELECT': , 'mjITEM_SLIDERINT': , 'mjITEM_SLIDERNUM': , 'mjITEM_EDITINT': , 'mjITEM_EDITNUM': , 'mjITEM_EDITFLOAT': , 'mjITEM_EDITTXT': , 'mjNITEM': } + mjITEM_BUTTON: typing.ClassVar[mjtItem] # value = + mjITEM_CHECKBYTE: typing.ClassVar[mjtItem] # value = + mjITEM_CHECKINT: typing.ClassVar[mjtItem] # value = + mjITEM_EDITFLOAT: typing.ClassVar[mjtItem] # value = + mjITEM_EDITINT: typing.ClassVar[mjtItem] # value = + mjITEM_EDITNUM: typing.ClassVar[mjtItem] # value = + mjITEM_EDITTXT: typing.ClassVar[mjtItem] # value = + mjITEM_END: typing.ClassVar[mjtItem] # value = + mjITEM_RADIO: typing.ClassVar[mjtItem] # value = + mjITEM_RADIOLINE: typing.ClassVar[mjtItem] # value = + mjITEM_SECTION: typing.ClassVar[mjtItem] # value = + mjITEM_SELECT: typing.ClassVar[mjtItem] # value = + mjITEM_SEPARATOR: typing.ClassVar[mjtItem] # value = + mjITEM_SLIDERINT: typing.ClassVar[mjtItem] # value = + mjITEM_SLIDERNUM: typing.ClassVar[mjtItem] # value = + mjITEM_STATIC: typing.ClassVar[mjtItem] # value = + mjNITEM: typing.ClassVar[mjtItem] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtJacobian: + """ + Members: + + mjJAC_DENSE + + mjJAC_SPARSE + + mjJAC_AUTO + """ + + __members__: typing.ClassVar[ + dict[str, mjtJacobian] + ] # value = {'mjJAC_DENSE': , 'mjJAC_SPARSE': , 'mjJAC_AUTO': } + mjJAC_AUTO: typing.ClassVar[mjtJacobian] # value = + mjJAC_DENSE: typing.ClassVar[mjtJacobian] # value = + mjJAC_SPARSE: typing.ClassVar[mjtJacobian] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtJoint: + """ + Members: + + mjJNT_FREE + + mjJNT_BALL + + mjJNT_SLIDE + + mjJNT_HINGE + """ + + __members__: typing.ClassVar[ + dict[str, mjtJoint] + ] # value = {'mjJNT_FREE': , 'mjJNT_BALL': , 'mjJNT_SLIDE': , 'mjJNT_HINGE': } + mjJNT_BALL: typing.ClassVar[mjtJoint] # value = + mjJNT_FREE: typing.ClassVar[mjtJoint] # value = + mjJNT_HINGE: typing.ClassVar[mjtJoint] # value = + mjJNT_SLIDE: typing.ClassVar[mjtJoint] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtLRMode: + """ + Members: + + mjLRMODE_NONE + + mjLRMODE_MUSCLE + + mjLRMODE_MUSCLEUSER + + mjLRMODE_ALL + """ + + __members__: typing.ClassVar[ + dict[str, mjtLRMode] + ] # value = {'mjLRMODE_NONE': , 'mjLRMODE_MUSCLE': , 'mjLRMODE_MUSCLEUSER': , 'mjLRMODE_ALL': } + mjLRMODE_ALL: typing.ClassVar[mjtLRMode] # value = + mjLRMODE_MUSCLE: typing.ClassVar[mjtLRMode] # value = + mjLRMODE_MUSCLEUSER: typing.ClassVar[ + mjtLRMode + ] # value = + mjLRMODE_NONE: typing.ClassVar[mjtLRMode] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtLabel: + """ + Members: + + mjLABEL_NONE + + mjLABEL_BODY + + mjLABEL_JOINT + + mjLABEL_GEOM + + mjLABEL_SITE + + mjLABEL_CAMERA + + mjLABEL_LIGHT + + mjLABEL_TENDON + + mjLABEL_ACTUATOR + + mjLABEL_CONSTRAINT + + mjLABEL_FLEX + + mjLABEL_SKIN + + mjLABEL_SELECTION + + mjLABEL_SELPNT + + mjLABEL_CONTACTPOINT + + mjLABEL_CONTACTFORCE + + mjLABEL_ISLAND + + mjNLABEL + """ + + __members__: typing.ClassVar[ + dict[str, mjtLabel] + ] # value = {'mjLABEL_NONE': , 'mjLABEL_BODY': , 'mjLABEL_JOINT': , 'mjLABEL_GEOM': , 'mjLABEL_SITE': , 'mjLABEL_CAMERA': , 'mjLABEL_LIGHT': , 'mjLABEL_TENDON': , 'mjLABEL_ACTUATOR': , 'mjLABEL_CONSTRAINT': , 'mjLABEL_FLEX': , 'mjLABEL_SKIN': , 'mjLABEL_SELECTION': , 'mjLABEL_SELPNT': , 'mjLABEL_CONTACTPOINT': , 'mjLABEL_CONTACTFORCE': , 'mjLABEL_ISLAND': , 'mjNLABEL': } + mjLABEL_ACTUATOR: typing.ClassVar[mjtLabel] # value = + mjLABEL_BODY: typing.ClassVar[mjtLabel] # value = + mjLABEL_CAMERA: typing.ClassVar[mjtLabel] # value = + mjLABEL_CONSTRAINT: typing.ClassVar[ + mjtLabel + ] # value = + mjLABEL_CONTACTFORCE: typing.ClassVar[ + mjtLabel + ] # value = + mjLABEL_CONTACTPOINT: typing.ClassVar[ + mjtLabel + ] # value = + mjLABEL_FLEX: typing.ClassVar[mjtLabel] # value = + mjLABEL_GEOM: typing.ClassVar[mjtLabel] # value = + mjLABEL_ISLAND: typing.ClassVar[mjtLabel] # value = + mjLABEL_JOINT: typing.ClassVar[mjtLabel] # value = + mjLABEL_LIGHT: typing.ClassVar[mjtLabel] # value = + mjLABEL_NONE: typing.ClassVar[mjtLabel] # value = + mjLABEL_SELECTION: typing.ClassVar[ + mjtLabel + ] # value = + mjLABEL_SELPNT: typing.ClassVar[mjtLabel] # value = + mjLABEL_SITE: typing.ClassVar[mjtLabel] # value = + mjLABEL_SKIN: typing.ClassVar[mjtLabel] # value = + mjLABEL_TENDON: typing.ClassVar[mjtLabel] # value = + mjNLABEL: typing.ClassVar[mjtLabel] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtLightType: + """ + Members: + + mjLIGHT_SPOT + + mjLIGHT_DIRECTIONAL + + mjLIGHT_POINT + + mjLIGHT_IMAGE + """ + + __members__: typing.ClassVar[ + dict[str, mjtLightType] + ] # value = {'mjLIGHT_SPOT': , 'mjLIGHT_DIRECTIONAL': , 'mjLIGHT_POINT': , 'mjLIGHT_IMAGE': } + mjLIGHT_DIRECTIONAL: typing.ClassVar[ + mjtLightType + ] # value = + mjLIGHT_IMAGE: typing.ClassVar[ + mjtLightType + ] # value = + mjLIGHT_POINT: typing.ClassVar[ + mjtLightType + ] # value = + mjLIGHT_SPOT: typing.ClassVar[mjtLightType] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtLimited: + """ + Members: + + mjLIMITED_FALSE + + mjLIMITED_TRUE + + mjLIMITED_AUTO + """ + + __members__: typing.ClassVar[ + dict[str, mjtLimited] + ] # value = {'mjLIMITED_FALSE': , 'mjLIMITED_TRUE': , 'mjLIMITED_AUTO': } + mjLIMITED_AUTO: typing.ClassVar[mjtLimited] # value = + mjLIMITED_FALSE: typing.ClassVar[ + mjtLimited + ] # value = + mjLIMITED_TRUE: typing.ClassVar[mjtLimited] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtMark: + """ + Members: + + mjMARK_NONE + + mjMARK_EDGE + + mjMARK_CROSS + + mjMARK_RANDOM + """ + + __members__: typing.ClassVar[ + dict[str, mjtMark] + ] # value = {'mjMARK_NONE': , 'mjMARK_EDGE': , 'mjMARK_CROSS': , 'mjMARK_RANDOM': } + mjMARK_CROSS: typing.ClassVar[mjtMark] # value = + mjMARK_EDGE: typing.ClassVar[mjtMark] # value = + mjMARK_NONE: typing.ClassVar[mjtMark] # value = + mjMARK_RANDOM: typing.ClassVar[mjtMark] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtMeshBuiltin: + """ + Members: + + mjMESH_BUILTIN_NONE + + mjMESH_BUILTIN_SPHERE + + mjMESH_BUILTIN_HEMISPHERE + + mjMESH_BUILTIN_CONE + + mjMESH_BUILTIN_SUPERSPHERE + + mjMESH_BUILTIN_SUPERTORUS + + mjMESH_BUILTIN_WEDGE + + mjMESH_BUILTIN_PLATE + """ + + __members__: typing.ClassVar[ + dict[str, mjtMeshBuiltin] + ] # value = {'mjMESH_BUILTIN_NONE': , 'mjMESH_BUILTIN_SPHERE': , 'mjMESH_BUILTIN_HEMISPHERE': , 'mjMESH_BUILTIN_CONE': , 'mjMESH_BUILTIN_SUPERSPHERE': , 'mjMESH_BUILTIN_SUPERTORUS': , 'mjMESH_BUILTIN_WEDGE': , 'mjMESH_BUILTIN_PLATE': } + mjMESH_BUILTIN_CONE: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + mjMESH_BUILTIN_HEMISPHERE: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + mjMESH_BUILTIN_NONE: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + mjMESH_BUILTIN_PLATE: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + mjMESH_BUILTIN_SPHERE: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + mjMESH_BUILTIN_SUPERSPHERE: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + mjMESH_BUILTIN_SUPERTORUS: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + mjMESH_BUILTIN_WEDGE: typing.ClassVar[ + mjtMeshBuiltin + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtMeshInertia: + """ + Members: + + mjMESH_INERTIA_CONVEX + + mjMESH_INERTIA_EXACT + + mjMESH_INERTIA_LEGACY + + mjMESH_INERTIA_SHELL + """ + + __members__: typing.ClassVar[ + dict[str, mjtMeshInertia] + ] # value = {'mjMESH_INERTIA_CONVEX': , 'mjMESH_INERTIA_EXACT': , 'mjMESH_INERTIA_LEGACY': , 'mjMESH_INERTIA_SHELL': } + mjMESH_INERTIA_CONVEX: typing.ClassVar[ + mjtMeshInertia + ] # value = + mjMESH_INERTIA_EXACT: typing.ClassVar[ + mjtMeshInertia + ] # value = + mjMESH_INERTIA_LEGACY: typing.ClassVar[ + mjtMeshInertia + ] # value = + mjMESH_INERTIA_SHELL: typing.ClassVar[ + mjtMeshInertia + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtMouse: + """ + Members: + + mjMOUSE_NONE + + mjMOUSE_ROTATE_V + + mjMOUSE_ROTATE_H + + mjMOUSE_MOVE_V + + mjMOUSE_MOVE_H + + mjMOUSE_ZOOM + + mjMOUSE_SELECT + """ + + __members__: typing.ClassVar[ + dict[str, mjtMouse] + ] # value = {'mjMOUSE_NONE': , 'mjMOUSE_ROTATE_V': , 'mjMOUSE_ROTATE_H': , 'mjMOUSE_MOVE_V': , 'mjMOUSE_MOVE_H': , 'mjMOUSE_ZOOM': , 'mjMOUSE_SELECT': } + mjMOUSE_MOVE_H: typing.ClassVar[mjtMouse] # value = + mjMOUSE_MOVE_V: typing.ClassVar[mjtMouse] # value = + mjMOUSE_NONE: typing.ClassVar[mjtMouse] # value = + mjMOUSE_ROTATE_H: typing.ClassVar[mjtMouse] # value = + mjMOUSE_ROTATE_V: typing.ClassVar[mjtMouse] # value = + mjMOUSE_SELECT: typing.ClassVar[mjtMouse] # value = + mjMOUSE_ZOOM: typing.ClassVar[mjtMouse] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtObj: + """ + Members: + + mjOBJ_UNKNOWN + + mjOBJ_BODY + + mjOBJ_XBODY + + mjOBJ_JOINT + + mjOBJ_DOF + + mjOBJ_GEOM + + mjOBJ_SITE + + mjOBJ_CAMERA + + mjOBJ_LIGHT + + mjOBJ_FLEX + + mjOBJ_MESH + + mjOBJ_SKIN + + mjOBJ_HFIELD + + mjOBJ_TEXTURE + + mjOBJ_MATERIAL + + mjOBJ_PAIR + + mjOBJ_EXCLUDE + + mjOBJ_EQUALITY + + mjOBJ_TENDON + + mjOBJ_ACTUATOR + + mjOBJ_SENSOR + + mjOBJ_NUMERIC + + mjOBJ_TEXT + + mjOBJ_TUPLE + + mjOBJ_KEY + + mjOBJ_PLUGIN + + mjNOBJECT + + mjOBJ_FRAME + + mjOBJ_DEFAULT + + mjOBJ_MODEL + """ + + __members__: typing.ClassVar[ + dict[str, mjtObj] + ] # value = {'mjOBJ_UNKNOWN': , 'mjOBJ_BODY': , 'mjOBJ_XBODY': , 'mjOBJ_JOINT': , 'mjOBJ_DOF': , 'mjOBJ_GEOM': , 'mjOBJ_SITE': , 'mjOBJ_CAMERA': , 'mjOBJ_LIGHT': , 'mjOBJ_FLEX': , 'mjOBJ_MESH': , 'mjOBJ_SKIN': , 'mjOBJ_HFIELD': , 'mjOBJ_TEXTURE': , 'mjOBJ_MATERIAL': , 'mjOBJ_PAIR': , 'mjOBJ_EXCLUDE': , 'mjOBJ_EQUALITY': , 'mjOBJ_TENDON': , 'mjOBJ_ACTUATOR': , 'mjOBJ_SENSOR': , 'mjOBJ_NUMERIC': , 'mjOBJ_TEXT': , 'mjOBJ_TUPLE': , 'mjOBJ_KEY': , 'mjOBJ_PLUGIN': , 'mjNOBJECT': , 'mjOBJ_FRAME': , 'mjOBJ_DEFAULT': , 'mjOBJ_MODEL': } + mjNOBJECT: typing.ClassVar[mjtObj] # value = + mjOBJ_ACTUATOR: typing.ClassVar[mjtObj] # value = + mjOBJ_BODY: typing.ClassVar[mjtObj] # value = + mjOBJ_CAMERA: typing.ClassVar[mjtObj] # value = + mjOBJ_DEFAULT: typing.ClassVar[mjtObj] # value = + mjOBJ_DOF: typing.ClassVar[mjtObj] # value = + mjOBJ_EQUALITY: typing.ClassVar[mjtObj] # value = + mjOBJ_EXCLUDE: typing.ClassVar[mjtObj] # value = + mjOBJ_FLEX: typing.ClassVar[mjtObj] # value = + mjOBJ_FRAME: typing.ClassVar[mjtObj] # value = + mjOBJ_GEOM: typing.ClassVar[mjtObj] # value = + mjOBJ_HFIELD: typing.ClassVar[mjtObj] # value = + mjOBJ_JOINT: typing.ClassVar[mjtObj] # value = + mjOBJ_KEY: typing.ClassVar[mjtObj] # value = + mjOBJ_LIGHT: typing.ClassVar[mjtObj] # value = + mjOBJ_MATERIAL: typing.ClassVar[mjtObj] # value = + mjOBJ_MESH: typing.ClassVar[mjtObj] # value = + mjOBJ_MODEL: typing.ClassVar[mjtObj] # value = + mjOBJ_NUMERIC: typing.ClassVar[mjtObj] # value = + mjOBJ_PAIR: typing.ClassVar[mjtObj] # value = + mjOBJ_PLUGIN: typing.ClassVar[mjtObj] # value = + mjOBJ_SENSOR: typing.ClassVar[mjtObj] # value = + mjOBJ_SITE: typing.ClassVar[mjtObj] # value = + mjOBJ_SKIN: typing.ClassVar[mjtObj] # value = + mjOBJ_TENDON: typing.ClassVar[mjtObj] # value = + mjOBJ_TEXT: typing.ClassVar[mjtObj] # value = + mjOBJ_TEXTURE: typing.ClassVar[mjtObj] # value = + mjOBJ_TUPLE: typing.ClassVar[mjtObj] # value = + mjOBJ_UNKNOWN: typing.ClassVar[mjtObj] # value = + mjOBJ_XBODY: typing.ClassVar[mjtObj] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtOrientation: + """ + Members: + + mjORIENTATION_QUAT + + mjORIENTATION_AXISANGLE + + mjORIENTATION_XYAXES + + mjORIENTATION_ZAXIS + + mjORIENTATION_EULER + """ + + __members__: typing.ClassVar[ + dict[str, mjtOrientation] + ] # value = {'mjORIENTATION_QUAT': , 'mjORIENTATION_AXISANGLE': , 'mjORIENTATION_XYAXES': , 'mjORIENTATION_ZAXIS': , 'mjORIENTATION_EULER': } + mjORIENTATION_AXISANGLE: typing.ClassVar[ + mjtOrientation + ] # value = + mjORIENTATION_EULER: typing.ClassVar[ + mjtOrientation + ] # value = + mjORIENTATION_QUAT: typing.ClassVar[ + mjtOrientation + ] # value = + mjORIENTATION_XYAXES: typing.ClassVar[ + mjtOrientation + ] # value = + mjORIENTATION_ZAXIS: typing.ClassVar[ + mjtOrientation + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtPertBit: + """ + Members: + + mjPERT_TRANSLATE + + mjPERT_ROTATE + """ + + __members__: typing.ClassVar[ + dict[str, mjtPertBit] + ] # value = {'mjPERT_TRANSLATE': , 'mjPERT_ROTATE': } + mjPERT_ROTATE: typing.ClassVar[mjtPertBit] # value = + mjPERT_TRANSLATE: typing.ClassVar[ + mjtPertBit + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtPluginCapabilityBit: + """ + Members: + + mjPLUGIN_ACTUATOR + + mjPLUGIN_SENSOR + + mjPLUGIN_PASSIVE + + mjPLUGIN_SDF + """ + + __members__: typing.ClassVar[ + dict[str, mjtPluginCapabilityBit] + ] # value = {'mjPLUGIN_ACTUATOR': , 'mjPLUGIN_SENSOR': , 'mjPLUGIN_PASSIVE': , 'mjPLUGIN_SDF': } + mjPLUGIN_ACTUATOR: typing.ClassVar[ + mjtPluginCapabilityBit + ] # value = + mjPLUGIN_PASSIVE: typing.ClassVar[ + mjtPluginCapabilityBit + ] # value = + mjPLUGIN_SDF: typing.ClassVar[ + mjtPluginCapabilityBit + ] # value = + mjPLUGIN_SENSOR: typing.ClassVar[ + mjtPluginCapabilityBit + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtRndFlag: + """ + Members: + + mjRND_SHADOW + + mjRND_WIREFRAME + + mjRND_REFLECTION + + mjRND_ADDITIVE + + mjRND_SKYBOX + + mjRND_FOG + + mjRND_HAZE + + mjRND_SEGMENT + + mjRND_IDCOLOR + + mjRND_CULL_FACE + + mjNRNDFLAG + """ + + __members__: typing.ClassVar[ + dict[str, mjtRndFlag] + ] # value = {'mjRND_SHADOW': , 'mjRND_WIREFRAME': , 'mjRND_REFLECTION': , 'mjRND_ADDITIVE': , 'mjRND_SKYBOX': , 'mjRND_FOG': , 'mjRND_HAZE': , 'mjRND_SEGMENT': , 'mjRND_IDCOLOR': , 'mjRND_CULL_FACE': , 'mjNRNDFLAG': } + mjNRNDFLAG: typing.ClassVar[mjtRndFlag] # value = + mjRND_ADDITIVE: typing.ClassVar[mjtRndFlag] # value = + mjRND_CULL_FACE: typing.ClassVar[ + mjtRndFlag + ] # value = + mjRND_FOG: typing.ClassVar[mjtRndFlag] # value = + mjRND_HAZE: typing.ClassVar[mjtRndFlag] # value = + mjRND_IDCOLOR: typing.ClassVar[mjtRndFlag] # value = + mjRND_REFLECTION: typing.ClassVar[ + mjtRndFlag + ] # value = + mjRND_SEGMENT: typing.ClassVar[mjtRndFlag] # value = + mjRND_SHADOW: typing.ClassVar[mjtRndFlag] # value = + mjRND_SKYBOX: typing.ClassVar[mjtRndFlag] # value = + mjRND_WIREFRAME: typing.ClassVar[ + mjtRndFlag + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtSDFType: + """ + Members: + + mjSDFTYPE_SINGLE + + mjSDFTYPE_INTERSECTION + + mjSDFTYPE_MIDSURFACE + + mjSDFTYPE_COLLISION + """ + + __members__: typing.ClassVar[ + dict[str, mjtSDFType] + ] # value = {'mjSDFTYPE_SINGLE': , 'mjSDFTYPE_INTERSECTION': , 'mjSDFTYPE_MIDSURFACE': , 'mjSDFTYPE_COLLISION': } + mjSDFTYPE_COLLISION: typing.ClassVar[ + mjtSDFType + ] # value = + mjSDFTYPE_INTERSECTION: typing.ClassVar[ + mjtSDFType + ] # value = + mjSDFTYPE_MIDSURFACE: typing.ClassVar[ + mjtSDFType + ] # value = + mjSDFTYPE_SINGLE: typing.ClassVar[ + mjtSDFType + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtSameFrame: + """ + Members: + + mjSAMEFRAME_NONE + + mjSAMEFRAME_BODY + + mjSAMEFRAME_INERTIA + + mjSAMEFRAME_BODYROT + + mjSAMEFRAME_INERTIAROT + """ + + __members__: typing.ClassVar[ + dict[str, mjtSameFrame] + ] # value = {'mjSAMEFRAME_NONE': , 'mjSAMEFRAME_BODY': , 'mjSAMEFRAME_INERTIA': , 'mjSAMEFRAME_BODYROT': , 'mjSAMEFRAME_INERTIAROT': } + mjSAMEFRAME_BODY: typing.ClassVar[ + mjtSameFrame + ] # value = + mjSAMEFRAME_BODYROT: typing.ClassVar[ + mjtSameFrame + ] # value = + mjSAMEFRAME_INERTIA: typing.ClassVar[ + mjtSameFrame + ] # value = + mjSAMEFRAME_INERTIAROT: typing.ClassVar[ + mjtSameFrame + ] # value = + mjSAMEFRAME_NONE: typing.ClassVar[ + mjtSameFrame + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtSection: + """ + Members: + + mjSECT_CLOSED + + mjSECT_OPEN + + mjSECT_FIXED + """ + + __members__: typing.ClassVar[ + dict[str, mjtSection] + ] # value = {'mjSECT_CLOSED': , 'mjSECT_OPEN': , 'mjSECT_FIXED': } + mjSECT_CLOSED: typing.ClassVar[mjtSection] # value = + mjSECT_FIXED: typing.ClassVar[mjtSection] # value = + mjSECT_OPEN: typing.ClassVar[mjtSection] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtSensor: + """ + Members: + + mjSENS_TOUCH + + mjSENS_ACCELEROMETER + + mjSENS_VELOCIMETER + + mjSENS_GYRO + + mjSENS_FORCE + + mjSENS_TORQUE + + mjSENS_MAGNETOMETER + + mjSENS_RANGEFINDER + + mjSENS_CAMPROJECTION + + mjSENS_JOINTPOS + + mjSENS_JOINTVEL + + mjSENS_TENDONPOS + + mjSENS_TENDONVEL + + mjSENS_ACTUATORPOS + + mjSENS_ACTUATORVEL + + mjSENS_ACTUATORFRC + + mjSENS_JOINTACTFRC + + mjSENS_TENDONACTFRC + + mjSENS_BALLQUAT + + mjSENS_BALLANGVEL + + mjSENS_JOINTLIMITPOS + + mjSENS_JOINTLIMITVEL + + mjSENS_JOINTLIMITFRC + + mjSENS_TENDONLIMITPOS + + mjSENS_TENDONLIMITVEL + + mjSENS_TENDONLIMITFRC + + mjSENS_FRAMEPOS + + mjSENS_FRAMEQUAT + + mjSENS_FRAMEXAXIS + + mjSENS_FRAMEYAXIS + + mjSENS_FRAMEZAXIS + + mjSENS_FRAMELINVEL + + mjSENS_FRAMEANGVEL + + mjSENS_FRAMELINACC + + mjSENS_FRAMEANGACC + + mjSENS_SUBTREECOM + + mjSENS_SUBTREELINVEL + + mjSENS_SUBTREEANGMOM + + mjSENS_INSIDESITE + + mjSENS_GEOMDIST + + mjSENS_GEOMNORMAL + + mjSENS_GEOMFROMTO + + mjSENS_CONTACT + + mjSENS_E_POTENTIAL + + mjSENS_E_KINETIC + + mjSENS_CLOCK + + mjSENS_TACTILE + + mjSENS_PLUGIN + + mjSENS_USER + """ + + __members__: typing.ClassVar[ + dict[str, mjtSensor] + ] # value = {'mjSENS_TOUCH': , 'mjSENS_ACCELEROMETER': , 'mjSENS_VELOCIMETER': , 'mjSENS_GYRO': , 'mjSENS_FORCE': , 'mjSENS_TORQUE': , 'mjSENS_MAGNETOMETER': , 'mjSENS_RANGEFINDER': , 'mjSENS_CAMPROJECTION': , 'mjSENS_JOINTPOS': , 'mjSENS_JOINTVEL': , 'mjSENS_TENDONPOS': , 'mjSENS_TENDONVEL': , 'mjSENS_ACTUATORPOS': , 'mjSENS_ACTUATORVEL': , 'mjSENS_ACTUATORFRC': , 'mjSENS_JOINTACTFRC': , 'mjSENS_TENDONACTFRC': , 'mjSENS_BALLQUAT': , 'mjSENS_BALLANGVEL': , 'mjSENS_JOINTLIMITPOS': , 'mjSENS_JOINTLIMITVEL': , 'mjSENS_JOINTLIMITFRC': , 'mjSENS_TENDONLIMITPOS': , 'mjSENS_TENDONLIMITVEL': , 'mjSENS_TENDONLIMITFRC': , 'mjSENS_FRAMEPOS': , 'mjSENS_FRAMEQUAT': , 'mjSENS_FRAMEXAXIS': , 'mjSENS_FRAMEYAXIS': , 'mjSENS_FRAMEZAXIS': , 'mjSENS_FRAMELINVEL': , 'mjSENS_FRAMEANGVEL': , 'mjSENS_FRAMELINACC': , 'mjSENS_FRAMEANGACC': , 'mjSENS_SUBTREECOM': , 'mjSENS_SUBTREELINVEL': , 'mjSENS_SUBTREEANGMOM': , 'mjSENS_INSIDESITE': , 'mjSENS_GEOMDIST': , 'mjSENS_GEOMNORMAL': , 'mjSENS_GEOMFROMTO': , 'mjSENS_CONTACT': , 'mjSENS_E_POTENTIAL': , 'mjSENS_E_KINETIC': , 'mjSENS_CLOCK': , 'mjSENS_TACTILE': , 'mjSENS_PLUGIN': , 'mjSENS_USER': } + mjSENS_ACCELEROMETER: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_ACTUATORFRC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_ACTUATORPOS: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_ACTUATORVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_BALLANGVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_BALLQUAT: typing.ClassVar[mjtSensor] # value = + mjSENS_CAMPROJECTION: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_CLOCK: typing.ClassVar[mjtSensor] # value = + mjSENS_CONTACT: typing.ClassVar[mjtSensor] # value = + mjSENS_E_KINETIC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_E_POTENTIAL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FORCE: typing.ClassVar[mjtSensor] # value = + mjSENS_FRAMEANGACC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FRAMEANGVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FRAMELINACC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FRAMELINVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FRAMEPOS: typing.ClassVar[mjtSensor] # value = + mjSENS_FRAMEQUAT: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FRAMEXAXIS: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FRAMEYAXIS: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_FRAMEZAXIS: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_GEOMDIST: typing.ClassVar[mjtSensor] # value = + mjSENS_GEOMFROMTO: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_GEOMNORMAL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_GYRO: typing.ClassVar[mjtSensor] # value = + mjSENS_INSIDESITE: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_JOINTACTFRC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_JOINTLIMITFRC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_JOINTLIMITPOS: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_JOINTLIMITVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_JOINTPOS: typing.ClassVar[mjtSensor] # value = + mjSENS_JOINTVEL: typing.ClassVar[mjtSensor] # value = + mjSENS_MAGNETOMETER: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_PLUGIN: typing.ClassVar[mjtSensor] # value = + mjSENS_RANGEFINDER: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_SUBTREEANGMOM: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_SUBTREECOM: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_SUBTREELINVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_TACTILE: typing.ClassVar[mjtSensor] # value = + mjSENS_TENDONACTFRC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_TENDONLIMITFRC: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_TENDONLIMITPOS: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_TENDONLIMITVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_TENDONPOS: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_TENDONVEL: typing.ClassVar[ + mjtSensor + ] # value = + mjSENS_TORQUE: typing.ClassVar[mjtSensor] # value = + mjSENS_TOUCH: typing.ClassVar[mjtSensor] # value = + mjSENS_USER: typing.ClassVar[mjtSensor] # value = + mjSENS_VELOCIMETER: typing.ClassVar[ + mjtSensor + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtSolver: + """ + Members: + + mjSOL_PGS + + mjSOL_CG + + mjSOL_NEWTON + """ + + __members__: typing.ClassVar[ + dict[str, mjtSolver] + ] # value = {'mjSOL_PGS': , 'mjSOL_CG': , 'mjSOL_NEWTON': } + mjSOL_CG: typing.ClassVar[mjtSolver] # value = + mjSOL_NEWTON: typing.ClassVar[mjtSolver] # value = + mjSOL_PGS: typing.ClassVar[mjtSolver] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtStage: + """ + Members: + + mjSTAGE_NONE + + mjSTAGE_POS + + mjSTAGE_VEL + + mjSTAGE_ACC + """ + + __members__: typing.ClassVar[ + dict[str, mjtStage] + ] # value = {'mjSTAGE_NONE': , 'mjSTAGE_POS': , 'mjSTAGE_VEL': , 'mjSTAGE_ACC': } + mjSTAGE_ACC: typing.ClassVar[mjtStage] # value = + mjSTAGE_NONE: typing.ClassVar[mjtStage] # value = + mjSTAGE_POS: typing.ClassVar[mjtStage] # value = + mjSTAGE_VEL: typing.ClassVar[mjtStage] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtState: + """ + Members: + + mjSTATE_TIME + + mjSTATE_QPOS + + mjSTATE_QVEL + + mjSTATE_ACT + + mjSTATE_WARMSTART + + mjSTATE_CTRL + + mjSTATE_QFRC_APPLIED + + mjSTATE_XFRC_APPLIED + + mjSTATE_EQ_ACTIVE + + mjSTATE_MOCAP_POS + + mjSTATE_MOCAP_QUAT + + mjSTATE_USERDATA + + mjSTATE_PLUGIN + + mjNSTATE + + mjSTATE_PHYSICS + + mjSTATE_FULLPHYSICS + + mjSTATE_USER + + mjSTATE_INTEGRATION + """ + + __members__: typing.ClassVar[ + dict[str, mjtState] + ] # value = {'mjSTATE_TIME': , 'mjSTATE_QPOS': , 'mjSTATE_QVEL': , 'mjSTATE_ACT': , 'mjSTATE_WARMSTART': , 'mjSTATE_CTRL': , 'mjSTATE_QFRC_APPLIED': , 'mjSTATE_XFRC_APPLIED': , 'mjSTATE_EQ_ACTIVE': , 'mjSTATE_MOCAP_POS': , 'mjSTATE_MOCAP_QUAT': , 'mjSTATE_USERDATA': , 'mjSTATE_PLUGIN': , 'mjNSTATE': , 'mjSTATE_PHYSICS': , 'mjSTATE_FULLPHYSICS': , 'mjSTATE_USER': , 'mjSTATE_INTEGRATION': } + mjNSTATE: typing.ClassVar[mjtState] # value = + mjSTATE_ACT: typing.ClassVar[mjtState] # value = + mjSTATE_CTRL: typing.ClassVar[mjtState] # value = + mjSTATE_EQ_ACTIVE: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_FULLPHYSICS: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_INTEGRATION: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_MOCAP_POS: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_MOCAP_QUAT: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_PHYSICS: typing.ClassVar[mjtState] # value = + mjSTATE_PLUGIN: typing.ClassVar[mjtState] # value = + mjSTATE_QFRC_APPLIED: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_QPOS: typing.ClassVar[mjtState] # value = + mjSTATE_QVEL: typing.ClassVar[mjtState] # value = + mjSTATE_TIME: typing.ClassVar[mjtState] # value = + mjSTATE_USER: typing.ClassVar[mjtState] # value = + mjSTATE_USERDATA: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_WARMSTART: typing.ClassVar[ + mjtState + ] # value = + mjSTATE_XFRC_APPLIED: typing.ClassVar[ + mjtState + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtStereo: + """ + Members: + + mjSTEREO_NONE + + mjSTEREO_QUADBUFFERED + + mjSTEREO_SIDEBYSIDE + """ + + __members__: typing.ClassVar[ + dict[str, mjtStereo] + ] # value = {'mjSTEREO_NONE': , 'mjSTEREO_QUADBUFFERED': , 'mjSTEREO_SIDEBYSIDE': } + mjSTEREO_NONE: typing.ClassVar[mjtStereo] # value = + mjSTEREO_QUADBUFFERED: typing.ClassVar[ + mjtStereo + ] # value = + mjSTEREO_SIDEBYSIDE: typing.ClassVar[ + mjtStereo + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtTaskStatus: + """ + Members: + + mjTASK_NEW + + mjTASK_QUEUED + + mjTASK_COMPLETED + """ + + __members__: typing.ClassVar[ + dict[str, mjtTaskStatus] + ] # value = {'mjTASK_NEW': , 'mjTASK_QUEUED': , 'mjTASK_COMPLETED': } + mjTASK_COMPLETED: typing.ClassVar[ + mjtTaskStatus + ] # value = + mjTASK_NEW: typing.ClassVar[mjtTaskStatus] # value = + mjTASK_QUEUED: typing.ClassVar[ + mjtTaskStatus + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtTexture: + """ + Members: + + mjTEXTURE_2D + + mjTEXTURE_CUBE + + mjTEXTURE_SKYBOX + """ + + __members__: typing.ClassVar[ + dict[str, mjtTexture] + ] # value = {'mjTEXTURE_2D': , 'mjTEXTURE_CUBE': , 'mjTEXTURE_SKYBOX': } + mjTEXTURE_2D: typing.ClassVar[mjtTexture] # value = + mjTEXTURE_CUBE: typing.ClassVar[mjtTexture] # value = + mjTEXTURE_SKYBOX: typing.ClassVar[ + mjtTexture + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtTextureRole: + """ + Members: + + mjTEXROLE_USER + + mjTEXROLE_RGB + + mjTEXROLE_OCCLUSION + + mjTEXROLE_ROUGHNESS + + mjTEXROLE_METALLIC + + mjTEXROLE_NORMAL + + mjTEXROLE_OPACITY + + mjTEXROLE_EMISSIVE + + mjTEXROLE_RGBA + + mjTEXROLE_ORM + + mjNTEXROLE + """ + + __members__: typing.ClassVar[ + dict[str, mjtTextureRole] + ] # value = {'mjTEXROLE_USER': , 'mjTEXROLE_RGB': , 'mjTEXROLE_OCCLUSION': , 'mjTEXROLE_ROUGHNESS': , 'mjTEXROLE_METALLIC': , 'mjTEXROLE_NORMAL': , 'mjTEXROLE_OPACITY': , 'mjTEXROLE_EMISSIVE': , 'mjTEXROLE_RGBA': , 'mjTEXROLE_ORM': , 'mjNTEXROLE': } + mjNTEXROLE: typing.ClassVar[mjtTextureRole] # value = + mjTEXROLE_EMISSIVE: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_METALLIC: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_NORMAL: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_OCCLUSION: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_OPACITY: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_ORM: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_RGB: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_RGBA: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_ROUGHNESS: typing.ClassVar[ + mjtTextureRole + ] # value = + mjTEXROLE_USER: typing.ClassVar[ + mjtTextureRole + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtTimer: + """ + Members: + + mjTIMER_STEP + + mjTIMER_FORWARD + + mjTIMER_INVERSE + + mjTIMER_POSITION + + mjTIMER_VELOCITY + + mjTIMER_ACTUATION + + mjTIMER_CONSTRAINT + + mjTIMER_ADVANCE + + mjTIMER_POS_KINEMATICS + + mjTIMER_POS_INERTIA + + mjTIMER_POS_COLLISION + + mjTIMER_POS_MAKE + + mjTIMER_POS_PROJECT + + mjTIMER_COL_BROAD + + mjTIMER_COL_NARROW + + mjNTIMER + """ + + __members__: typing.ClassVar[ + dict[str, mjtTimer] + ] # value = {'mjTIMER_STEP': , 'mjTIMER_FORWARD': , 'mjTIMER_INVERSE': , 'mjTIMER_POSITION': , 'mjTIMER_VELOCITY': , 'mjTIMER_ACTUATION': , 'mjTIMER_CONSTRAINT': , 'mjTIMER_ADVANCE': , 'mjTIMER_POS_KINEMATICS': , 'mjTIMER_POS_INERTIA': , 'mjTIMER_POS_COLLISION': , 'mjTIMER_POS_MAKE': , 'mjTIMER_POS_PROJECT': , 'mjTIMER_COL_BROAD': , 'mjTIMER_COL_NARROW': , 'mjNTIMER': } + mjNTIMER: typing.ClassVar[mjtTimer] # value = + mjTIMER_ACTUATION: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_ADVANCE: typing.ClassVar[mjtTimer] # value = + mjTIMER_COL_BROAD: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_COL_NARROW: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_CONSTRAINT: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_FORWARD: typing.ClassVar[mjtTimer] # value = + mjTIMER_INVERSE: typing.ClassVar[mjtTimer] # value = + mjTIMER_POSITION: typing.ClassVar[mjtTimer] # value = + mjTIMER_POS_COLLISION: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_POS_INERTIA: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_POS_KINEMATICS: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_POS_MAKE: typing.ClassVar[mjtTimer] # value = + mjTIMER_POS_PROJECT: typing.ClassVar[ + mjtTimer + ] # value = + mjTIMER_STEP: typing.ClassVar[mjtTimer] # value = + mjTIMER_VELOCITY: typing.ClassVar[mjtTimer] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtTrn: + """ + Members: + + mjTRN_JOINT + + mjTRN_JOINTINPARENT + + mjTRN_SLIDERCRANK + + mjTRN_TENDON + + mjTRN_SITE + + mjTRN_BODY + + mjTRN_UNDEFINED + """ + + __members__: typing.ClassVar[ + dict[str, mjtTrn] + ] # value = {'mjTRN_JOINT': , 'mjTRN_JOINTINPARENT': , 'mjTRN_SLIDERCRANK': , 'mjTRN_TENDON': , 'mjTRN_SITE': , 'mjTRN_BODY': , 'mjTRN_UNDEFINED': } + mjTRN_BODY: typing.ClassVar[mjtTrn] # value = + mjTRN_JOINT: typing.ClassVar[mjtTrn] # value = + mjTRN_JOINTINPARENT: typing.ClassVar[ + mjtTrn + ] # value = + mjTRN_SITE: typing.ClassVar[mjtTrn] # value = + mjTRN_SLIDERCRANK: typing.ClassVar[mjtTrn] # value = + mjTRN_TENDON: typing.ClassVar[mjtTrn] # value = + mjTRN_UNDEFINED: typing.ClassVar[mjtTrn] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtVisFlag: + """ + Members: + + mjVIS_CONVEXHULL + + mjVIS_TEXTURE + + mjVIS_JOINT + + mjVIS_CAMERA + + mjVIS_ACTUATOR + + mjVIS_ACTIVATION + + mjVIS_LIGHT + + mjVIS_TENDON + + mjVIS_RANGEFINDER + + mjVIS_CONSTRAINT + + mjVIS_INERTIA + + mjVIS_SCLINERTIA + + mjVIS_PERTFORCE + + mjVIS_PERTOBJ + + mjVIS_CONTACTPOINT + + mjVIS_ISLAND + + mjVIS_CONTACTFORCE + + mjVIS_CONTACTSPLIT + + mjVIS_TRANSPARENT + + mjVIS_AUTOCONNECT + + mjVIS_COM + + mjVIS_SELECT + + mjVIS_STATIC + + mjVIS_SKIN + + mjVIS_FLEXVERT + + mjVIS_FLEXEDGE + + mjVIS_FLEXFACE + + mjVIS_FLEXSKIN + + mjVIS_BODYBVH + + mjVIS_MESHBVH + + mjVIS_SDFITER + + mjNVISFLAG + """ + + __members__: typing.ClassVar[ + dict[str, mjtVisFlag] + ] # value = {'mjVIS_CONVEXHULL': , 'mjVIS_TEXTURE': , 'mjVIS_JOINT': , 'mjVIS_CAMERA': , 'mjVIS_ACTUATOR': , 'mjVIS_ACTIVATION': , 'mjVIS_LIGHT': , 'mjVIS_TENDON': , 'mjVIS_RANGEFINDER': , 'mjVIS_CONSTRAINT': , 'mjVIS_INERTIA': , 'mjVIS_SCLINERTIA': , 'mjVIS_PERTFORCE': , 'mjVIS_PERTOBJ': , 'mjVIS_CONTACTPOINT': , 'mjVIS_ISLAND': , 'mjVIS_CONTACTFORCE': , 'mjVIS_CONTACTSPLIT': , 'mjVIS_TRANSPARENT': , 'mjVIS_AUTOCONNECT': , 'mjVIS_COM': , 'mjVIS_SELECT': , 'mjVIS_STATIC': , 'mjVIS_SKIN': , 'mjVIS_FLEXVERT': , 'mjVIS_FLEXEDGE': , 'mjVIS_FLEXFACE': , 'mjVIS_FLEXSKIN': , 'mjVIS_BODYBVH': , 'mjVIS_MESHBVH': , 'mjVIS_SDFITER': , 'mjNVISFLAG': } + mjNVISFLAG: typing.ClassVar[mjtVisFlag] # value = + mjVIS_ACTIVATION: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_ACTUATOR: typing.ClassVar[mjtVisFlag] # value = + mjVIS_AUTOCONNECT: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_BODYBVH: typing.ClassVar[mjtVisFlag] # value = + mjVIS_CAMERA: typing.ClassVar[mjtVisFlag] # value = + mjVIS_COM: typing.ClassVar[mjtVisFlag] # value = + mjVIS_CONSTRAINT: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_CONTACTFORCE: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_CONTACTPOINT: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_CONTACTSPLIT: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_CONVEXHULL: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_FLEXEDGE: typing.ClassVar[mjtVisFlag] # value = + mjVIS_FLEXFACE: typing.ClassVar[mjtVisFlag] # value = + mjVIS_FLEXSKIN: typing.ClassVar[mjtVisFlag] # value = + mjVIS_FLEXVERT: typing.ClassVar[mjtVisFlag] # value = + mjVIS_INERTIA: typing.ClassVar[mjtVisFlag] # value = + mjVIS_ISLAND: typing.ClassVar[mjtVisFlag] # value = + mjVIS_JOINT: typing.ClassVar[mjtVisFlag] # value = + mjVIS_LIGHT: typing.ClassVar[mjtVisFlag] # value = + mjVIS_MESHBVH: typing.ClassVar[mjtVisFlag] # value = + mjVIS_PERTFORCE: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_PERTOBJ: typing.ClassVar[mjtVisFlag] # value = + mjVIS_RANGEFINDER: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_SCLINERTIA: typing.ClassVar[ + mjtVisFlag + ] # value = + mjVIS_SDFITER: typing.ClassVar[mjtVisFlag] # value = + mjVIS_SELECT: typing.ClassVar[mjtVisFlag] # value = + mjVIS_SKIN: typing.ClassVar[mjtVisFlag] # value = + mjVIS_STATIC: typing.ClassVar[mjtVisFlag] # value = + mjVIS_TENDON: typing.ClassVar[mjtVisFlag] # value = + mjVIS_TEXTURE: typing.ClassVar[mjtVisFlag] # value = + mjVIS_TRANSPARENT: typing.ClassVar[ + mjtVisFlag + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtWarning: + """ + Members: + + mjWARN_INERTIA + + mjWARN_CONTACTFULL + + mjWARN_CNSTRFULL + + mjWARN_VGEOMFULL + + mjWARN_BADQPOS + + mjWARN_BADQVEL + + mjWARN_BADQACC + + mjWARN_BADCTRL + + mjNWARNING + """ + + __members__: typing.ClassVar[ + dict[str, mjtWarning] + ] # value = {'mjWARN_INERTIA': , 'mjWARN_CONTACTFULL': , 'mjWARN_CNSTRFULL': , 'mjWARN_VGEOMFULL': , 'mjWARN_BADQPOS': , 'mjWARN_BADQVEL': , 'mjWARN_BADQACC': , 'mjWARN_BADCTRL': , 'mjNWARNING': } + mjNWARNING: typing.ClassVar[mjtWarning] # value = + mjWARN_BADCTRL: typing.ClassVar[mjtWarning] # value = + mjWARN_BADQACC: typing.ClassVar[mjtWarning] # value = + mjWARN_BADQPOS: typing.ClassVar[mjtWarning] # value = + mjWARN_BADQVEL: typing.ClassVar[mjtWarning] # value = + mjWARN_CNSTRFULL: typing.ClassVar[ + mjtWarning + ] # value = + mjWARN_CONTACTFULL: typing.ClassVar[ + mjtWarning + ] # value = + mjWARN_INERTIA: typing.ClassVar[mjtWarning] # value = + mjWARN_VGEOMFULL: typing.ClassVar[ + mjtWarning + ] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class mjtWrap: + """ + Members: + + mjWRAP_NONE + + mjWRAP_JOINT + + mjWRAP_PULLEY + + mjWRAP_SITE + + mjWRAP_SPHERE + + mjWRAP_CYLINDER + """ + + __members__: typing.ClassVar[ + dict[str, mjtWrap] + ] # value = {'mjWRAP_NONE': , 'mjWRAP_JOINT': , 'mjWRAP_PULLEY': , 'mjWRAP_SITE': , 'mjWRAP_SPHERE': , 'mjWRAP_CYLINDER': } + mjWRAP_CYLINDER: typing.ClassVar[mjtWrap] # value = + mjWRAP_JOINT: typing.ClassVar[mjtWrap] # value = + mjWRAP_NONE: typing.ClassVar[mjtWrap] # value = + mjWRAP_PULLEY: typing.ClassVar[mjtWrap] # value = + mjWRAP_SITE: typing.ClassVar[mjtWrap] # value = + mjWRAP_SPHERE: typing.ClassVar[mjtWrap] # value = + @typing.overload + def __add__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __add__(self, arg0: typing.SupportsFloat) -> float: ... + def __and__(self, arg0: typing.SupportsInt) -> int: ... + def __eq__(self, other: typing.Any) -> bool: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __floordiv__(self, arg0: typing.SupportsFloat) -> float: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + @typing.overload + def __init__(self, value: typing.SupportsInt) -> None: ... + def __int__(self) -> int: ... + def __lshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __mul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ne__(self, other: typing.Any) -> bool: ... + def __neg__(self) -> int: ... + def __or__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __radd__(self, arg0: typing.SupportsFloat) -> float: ... + def __rand__(self, arg0: typing.SupportsInt) -> int: ... + def __repr__(self) -> str: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rfloordiv__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmod__(self, arg0: typing.SupportsFloat) -> float: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rmul__(self, arg0: typing.SupportsFloat) -> float: ... + def __ror__(self, arg0: typing.SupportsInt) -> int: ... + def __rshift__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __rsub__(self, arg0: typing.SupportsFloat) -> float: ... + def __rtruediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __rxor__(self, arg0: typing.SupportsInt) -> int: ... + def __setstate__(self, state: typing.SupportsInt) -> None: ... + def __str__(self) -> str: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsInt) -> int: ... + @typing.overload + def __sub__(self, arg0: typing.SupportsFloat) -> float: ... + def __truediv__(self, arg0: typing.SupportsFloat) -> float: ... + def __xor__(self, arg0: typing.SupportsInt) -> int: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... diff --git a/typings/mujoco/_errors.pyi b/typings/mujoco/_errors.pyi new file mode 100644 index 000000000..6ae8b3a1b --- /dev/null +++ b/typings/mujoco/_errors.pyi @@ -0,0 +1,5 @@ +from __future__ import annotations +from mujoco import FatalError +from mujoco import UnexpectedError + +__all__: list[str] = ["FatalError", "UnexpectedError"] diff --git a/typings/mujoco/_functions.pyi b/typings/mujoco/_functions.pyi new file mode 100644 index 000000000..38d16727d --- /dev/null +++ b/typings/mujoco/_functions.pyi @@ -0,0 +1,2825 @@ +from __future__ import annotations +import mujoco._structs +import numpy +import numpy.typing +import typing + +__all__: list[str] = [ + "mj_Euler", + "mj_RungeKutta", + "mj_addContact", + "mj_addM", + "mj_angmomMat", + "mj_applyFT", + "mj_camlight", + "mj_checkAcc", + "mj_checkPos", + "mj_checkVel", + "mj_collision", + "mj_comPos", + "mj_comVel", + "mj_compareFwdInv", + "mj_constraintUpdate", + "mj_contactForce", + "mj_crb", + "mj_defaultLROpt", + "mj_defaultOption", + "mj_defaultSolRefImp", + "mj_defaultVisual", + "mj_differentiatePos", + "mj_energyPos", + "mj_energyVel", + "mj_factorM", + "mj_flex", + "mj_forward", + "mj_forwardSkip", + "mj_fullM", + "mj_fwdAcceleration", + "mj_fwdActuation", + "mj_fwdConstraint", + "mj_fwdPosition", + "mj_fwdVelocity", + "mj_geomDistance", + "mj_getState", + "mj_getTotalmass", + "mj_id2name", + "mj_implicit", + "mj_integratePos", + "mj_invConstraint", + "mj_invPosition", + "mj_invVelocity", + "mj_inverse", + "mj_inverseSkip", + "mj_isDual", + "mj_isPyramidal", + "mj_isSparse", + "mj_island", + "mj_jac", + "mj_jacBody", + "mj_jacBodyCom", + "mj_jacDot", + "mj_jacGeom", + "mj_jacPointAxis", + "mj_jacSite", + "mj_jacSubtreeCom", + "mj_kinematics", + "mj_loadAllPluginLibraries", + "mj_loadPluginLibrary", + "mj_local2Global", + "mj_makeConstraint", + "mj_makeM", + "mj_mulJacTVec", + "mj_mulJacVec", + "mj_mulM", + "mj_mulM2", + "mj_multiRay", + "mj_name2id", + "mj_normalizeQuat", + "mj_objectAcceleration", + "mj_objectVelocity", + "mj_passive", + "mj_printData", + "mj_printFormattedData", + "mj_printFormattedModel", + "mj_printModel", + "mj_printSchema", + "mj_projectConstraint", + "mj_ray", + "mj_rayHfield", + "mj_rayMesh", + "mj_referenceConstraint", + "mj_resetCallbacks", + "mj_resetData", + "mj_resetDataDebug", + "mj_resetDataKeyframe", + "mj_rne", + "mj_rnePostConstraint", + "mj_saveLastXML", + "mj_saveModel", + "mj_sensorAcc", + "mj_sensorPos", + "mj_sensorVel", + "mj_setConst", + "mj_setKeyframe", + "mj_setLengthRange", + "mj_setState", + "mj_setTotalmass", + "mj_sizeModel", + "mj_solveM", + "mj_solveM2", + "mj_stateSize", + "mj_step", + "mj_step1", + "mj_step2", + "mj_subtreeVel", + "mj_tendon", + "mj_transmission", + "mj_version", + "mj_versionString", + "mjd_inverseFD", + "mjd_quatIntegrate", + "mjd_subQuat", + "mjd_transitionFD", + "mju_Halton", + "mju_L1", + "mju_add", + "mju_add3", + "mju_addScl", + "mju_addScl3", + "mju_addTo", + "mju_addTo3", + "mju_addToScl", + "mju_addToScl3", + "mju_axisAngle2Quat", + "mju_band2Dense", + "mju_bandDiag", + "mju_bandMulMatVec", + "mju_boxQP", + "mju_cholFactor", + "mju_cholFactorBand", + "mju_cholSolve", + "mju_cholSolveBand", + "mju_cholUpdate", + "mju_clip", + "mju_copy", + "mju_copy3", + "mju_copy4", + "mju_cross", + "mju_d2n", + "mju_decodePyramid", + "mju_dense2Band", + "mju_dense2sparse", + "mju_derivQuat", + "mju_dist3", + "mju_dot", + "mju_dot3", + "mju_eig3", + "mju_encodePyramid", + "mju_euler2Quat", + "mju_eye", + "mju_f2n", + "mju_fill", + "mju_insertionSort", + "mju_insertionSortInt", + "mju_isBad", + "mju_isZero", + "mju_mat2Quat", + "mju_mat2Rot", + "mju_max", + "mju_min", + "mju_mulMatMat", + "mju_mulMatMatT", + "mju_mulMatTMat", + "mju_mulMatTVec", + "mju_mulMatTVec3", + "mju_mulMatVec", + "mju_mulMatVec3", + "mju_mulPose", + "mju_mulQuat", + "mju_mulQuatAxis", + "mju_mulVecMatVec", + "mju_muscleBias", + "mju_muscleDynamics", + "mju_muscleGain", + "mju_n2d", + "mju_n2f", + "mju_negPose", + "mju_negQuat", + "mju_norm", + "mju_norm3", + "mju_normalize", + "mju_normalize3", + "mju_normalize4", + "mju_printMat", + "mju_printMatSparse", + "mju_quat2Mat", + "mju_quat2Vel", + "mju_quatIntegrate", + "mju_quatZ2Vec", + "mju_rayFlex", + "mju_rayGeom", + "mju_raySkin", + "mju_rotVecQuat", + "mju_round", + "mju_scl", + "mju_scl3", + "mju_sigmoid", + "mju_sign", + "mju_sparse2dense", + "mju_springDamper", + "mju_sqrMatTD", + "mju_standardNormal", + "mju_str2Type", + "mju_sub", + "mju_sub3", + "mju_subFrom", + "mju_subFrom3", + "mju_subQuat", + "mju_sum", + "mju_symmetrize", + "mju_transformSpatial", + "mju_transpose", + "mju_trnVecPose", + "mju_type2Str", + "mju_unit4", + "mju_warningText", + "mju_writeLog", + "mju_writeNumBytes", + "mju_zero", + "mju_zero3", + "mju_zero4", + "mjv_addGeoms", + "mjv_alignToCamera", + "mjv_applyPerturbForce", + "mjv_applyPerturbPose", + "mjv_cameraInModel", + "mjv_cameraInRoom", + "mjv_connector", + "mjv_defaultCamera", + "mjv_defaultFigure", + "mjv_defaultFreeCamera", + "mjv_defaultOption", + "mjv_defaultPerturb", + "mjv_frustumHeight", + "mjv_initGeom", + "mjv_initPerturb", + "mjv_makeLights", + "mjv_model2room", + "mjv_moveCamera", + "mjv_moveModel", + "mjv_movePerturb", + "mjv_room2model", + "mjv_select", + "mjv_updateCamera", + "mjv_updateScene", + "mjv_updateSkin", +] + +def _realloc_con_efc( + d: mujoco._structs.MjData, + ncon: typing.SupportsInt, + nefc: typing.SupportsInt, + nJ: typing.SupportsInt = -1, +) -> None: ... +def mj_Euler(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Euler integrator, semi-implicit in velocity. + """ + +def mj_RungeKutta( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, N: typing.SupportsInt +) -> None: + """ + Runge-Kutta explicit order-N integrator. + """ + +def mj_addContact( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, con: mujoco._structs.MjContact +) -> int: + """ + Add contact to d->contact list; return 0 if success; 1 if buffer full. + """ + +def mj_addM( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + dst: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + rownnz: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], + rowadr: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], + colind: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], +) -> None: + """ + Add inertia matrix to destination matrix. Destination can be sparse or dense when all int* are NULL. + """ + +def mj_angmomMat( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + body: typing.SupportsInt, +) -> None: + """ + Compute subtree angular momentum matrix. + """ + +def mj_applyFT( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + force: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + torque: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + point: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + body: typing.SupportsInt, + qfrc_target: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> None: + """ + Apply Cartesian force and torque (outside xfrc_applied mechanism). + """ + +def mj_camlight(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute camera and light positions and orientations. + """ + +def mj_checkAcc(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Check qacc, reset if any element is too big or nan. + """ + +def mj_checkPos(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Check qpos, reset if any element is too big or nan. + """ + +def mj_checkVel(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Check qvel, reset if any element is too big or nan. + """ + +def mj_collision(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run collision detection. + """ + +def mj_comPos(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Map inertias and motion dofs to global frame centered at CoM. + """ + +def mj_comVel(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute cvel, cdof_dot. + """ + +def mj_compareFwdInv(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compare forward and inverse dynamics, save results in fwdinv. + """ + +def mj_constraintUpdate( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jar: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + cost: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[1, 1]", "flags.writeable" + ] + | None, + flg_coneHessian: typing.SupportsInt, +) -> None: + """ + Compute efc_state, efc_force, qfrc_constraint, and (optionally) cone Hessians. If cost is not NULL, set *cost = s(jar) where jar = Jac*qacc-aref. + """ + +def mj_contactForce( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + id: typing.SupportsInt, + result: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable" + ], +) -> None: + """ + Extract 6D force:torque given contact id, in the contact frame. + """ + +def mj_crb(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run composite rigid body inertia algorithm (CRB). + """ + +def mj_defaultLROpt(opt: mujoco._structs.MjLROpt) -> None: + """ + Set default options for length range computation. + """ + +def mj_defaultOption(opt: mujoco._structs.MjOption) -> None: + """ + Set physics options to default values. + """ + +def mj_defaultSolRefImp( + solref: typing.SupportsFloat, solimp: typing.SupportsFloat +) -> None: + """ + Set solver parameters to default values. + """ + +def mj_defaultVisual(vis: mujoco._structs.MjVisual) -> None: + """ + Set visual options to default values. + """ + +def mj_differentiatePos( + m: mujoco._structs.MjModel, + qvel: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + dt: typing.SupportsFloat, + qpos1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + qpos2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Compute velocity by finite-differencing two positions. + """ + +def mj_energyPos(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Evaluate position-dependent energy (potential). + """ + +def mj_energyVel(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Evaluate velocity-dependent energy (kinetic). + """ + +def mj_factorM(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute sparse L'*D*L factorizaton of inertia matrix. + """ + +def mj_flex(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute flex-related quantities. + """ + +def mj_forward(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Forward dynamics: same as mj_step but do not integrate in time. + """ + +def mj_forwardSkip( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + skipstage: typing.SupportsInt, + skipsensor: typing.SupportsInt, +) -> None: + """ + Forward dynamics with skip; skipstage is mjtStage. + """ + +def mj_fullM( + m: mujoco._structs.MjModel, + dst: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + M: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Convert sparse inertia matrix M into full (i.e. dense) matrix. + """ + +def mj_fwdAcceleration(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Add up all non-constraint forces, compute qacc_smooth. + """ + +def mj_fwdActuation(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute actuator force qfrc_actuator. + """ + +def mj_fwdConstraint(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run selected constraint solver. + """ + +def mj_fwdPosition(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run position-dependent computations. + """ + +def mj_fwdVelocity(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run velocity-dependent computations. + """ + +def mj_geomDistance( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + geom1: typing.SupportsInt, + geom2: typing.SupportsInt, + distmax: typing.SupportsFloat, + fromto: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, +) -> float: + """ + Returns smallest signed distance between two geoms and optionally segment from geom1 to geom2. + """ + +def mj_getState( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + state: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + sig: typing.SupportsInt, +) -> None: + """ + Get state. + """ + +def mj_getTotalmass(m: mujoco._structs.MjModel) -> float: + """ + Sum all body masses. + """ + +def mj_id2name( + m: mujoco._structs.MjModel, type: typing.SupportsInt, id: typing.SupportsInt +) -> str: + """ + Get name of object with the specified mjtObj type and id, returns NULL if name not found. + """ + +def mj_implicit(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Implicit-in-velocity integrators. + """ + +def mj_integratePos( + m: mujoco._structs.MjModel, + qpos: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + qvel: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + dt: typing.SupportsFloat, +) -> None: + """ + Integrate position with given velocity. + """ + +def mj_invConstraint(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Apply the analytical formula for inverse constraint dynamics. + """ + +def mj_invPosition(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run position-dependent computations in inverse dynamics. + """ + +def mj_invVelocity(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run velocity-dependent computations in inverse dynamics. + """ + +def mj_inverse(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Inverse dynamics: qacc must be set before calling. + """ + +def mj_inverseSkip( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + skipstage: typing.SupportsInt, + skipsensor: typing.SupportsInt, +) -> None: + """ + Inverse dynamics with skip; skipstage is mjtStage. + """ + +def mj_isDual(m: mujoco._structs.MjModel) -> int: + """ + Determine type of solver (PGS is dual, CG and Newton are primal). + """ + +def mj_isPyramidal(m: mujoco._structs.MjModel) -> int: + """ + Determine type of friction cone. + """ + +def mj_isSparse(m: mujoco._structs.MjModel) -> int: + """ + Determine type of constraint Jacobian. + """ + +def mj_island(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Find constraint islands. + """ + +def mj_jac( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacp: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + jacr: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + point: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + body: typing.SupportsInt, +) -> None: + """ + Compute 3/6-by-nv end-effector Jacobian of global point attached to given body. + """ + +def mj_jacBody( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacp: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + jacr: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + body: typing.SupportsInt, +) -> None: + """ + Compute body frame end-effector Jacobian. + """ + +def mj_jacBodyCom( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacp: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + jacr: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + body: typing.SupportsInt, +) -> None: + """ + Compute body center-of-mass end-effector Jacobian. + """ + +def mj_jacDot( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacp: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + jacr: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + point: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + body: typing.SupportsInt, +) -> None: + """ + Compute 3/6-by-nv Jacobian time derivative of global point attached to given body. + """ + +def mj_jacGeom( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacp: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + jacr: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + geom: typing.SupportsInt, +) -> None: + """ + Compute geom end-effector Jacobian. + """ + +def mj_jacPointAxis( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacPoint: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + jacAxis: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + point: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + axis: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + body: typing.SupportsInt, +) -> None: + """ + Compute translation end-effector Jacobian of point, and rotation Jacobian of axis. + """ + +def mj_jacSite( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacp: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + jacr: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + site: typing.SupportsInt, +) -> None: + """ + Compute site end-effector Jacobian. + """ + +def mj_jacSubtreeCom( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + jacp: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + body: typing.SupportsInt, +) -> None: + """ + Compute subtree center-of-mass end-effector Jacobian. + """ + +def mj_kinematics(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Run forward kinematics. + """ + +def mj_loadAllPluginLibraries(directory: str) -> None: + """ + Scan a directory and load all dynamic libraries. Dynamic libraries in the specified directory are assumed to register one or more plugins. Optionally, if a callback is specified, it is called for each dynamic library encountered that registers plugins. + """ + +def mj_loadPluginLibrary(path: str) -> None: + """ + Load a dynamic library. The dynamic library is assumed to register one or more plugins. + """ + +def mj_local2Global( + d: mujoco._structs.MjData, + xpos: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + xmat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[9, 1]", "flags.writeable" + ], + pos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + body: typing.SupportsInt, + sameframe: typing.SupportsInt, +) -> None: + """ + Map from body local to global Cartesian coordinates, sameframe takes values from mjtSameFrame. + """ + +def mj_makeConstraint(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Construct constraints. + """ + +def mj_makeM(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Make inertia matrix. + """ + +def mj_mulJacTVec( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Multiply dense or sparse constraint Jacobian transpose by vector. + """ + +def mj_mulJacVec( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Multiply dense or sparse constraint Jacobian by vector. + """ + +def mj_mulM( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Multiply vector by inertia matrix. + """ + +def mj_mulM2( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Multiply vector by (inertia matrix)^(1/2). + """ + +def mj_multiRay( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + pnt: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + geomgroup: typing.Annotated[numpy.typing.NDArray[numpy.uint8], "[6, 1]"] | None, + flg_static: typing.SupportsInt, + bodyexclude: typing.SupportsInt, + geomid: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], + dist: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + nray: typing.SupportsInt, + cutoff: typing.SupportsFloat, +) -> None: + """ + Intersect multiple rays emanating from a single point. Similar semantics to mj_ray, but vec is an array of (nray x 3) directions. + """ + +def mj_name2id(m: mujoco._structs.MjModel, type: typing.SupportsInt, name: str) -> int: + """ + Get id of object with the specified mjtObj type and name, returns -1 if id not found. + """ + +def mj_normalizeQuat( + m: mujoco._structs.MjModel, + qpos: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> None: + """ + Normalize all quaternions in qpos-type vector. + """ + +def mj_objectAcceleration( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + objtype: typing.SupportsInt, + objid: typing.SupportsInt, + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable" + ], + flg_local: typing.SupportsInt, +) -> None: + """ + Compute object 6D acceleration (rot:lin) in object-centered frame, world/local orientation. + """ + +def mj_objectVelocity( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + objtype: typing.SupportsInt, + objid: typing.SupportsInt, + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable" + ], + flg_local: typing.SupportsInt, +) -> None: + """ + Compute object 6D velocity (rot:lin) in object-centered frame, world/local orientation. + """ + +def mj_passive(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces. + """ + +def mj_printData( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, filename: str +) -> None: + """ + Print data to text file. + """ + +def mj_printFormattedData( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + filename: str, + float_format: str, +) -> None: + """ + Print mjData to text file, specifying format. float_format must be a valid printf-style format string for a single float value + """ + +def mj_printFormattedModel( + m: mujoco._structs.MjModel, filename: str, float_format: str +) -> None: + """ + Print mjModel to text file, specifying format. float_format must be a valid printf-style format string for a single float value. + """ + +def mj_printModel(m: mujoco._structs.MjModel, filename: str) -> None: + """ + Print model to text file. + """ + +def mj_printSchema(flg_html: bool, flg_pad: bool) -> str: + """ + Print internal XML schema as plain text or HTML, with style-padding or  . + """ + +def mj_projectConstraint(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute inverse constraint inertia efc_AR. + """ + +def mj_ray( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + pnt: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + geomgroup: typing.Annotated[numpy.typing.NDArray[numpy.uint8], "[6, 1]"] | None, + flg_static: typing.SupportsInt, + bodyexclude: typing.SupportsInt, + geomid: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[1, 1]", "flags.writeable" + ], +) -> float: + """ + Intersect ray (pnt+x*vec, x>=0) with visible geoms, except geoms in bodyexclude. Return distance (x) to nearest surface, or -1 if no intersection and output geomid. geomgroup, flg_static are as in mjvOption; geomgroup==NULL skips group exclusion. + """ + +def mj_rayHfield( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + geomid: typing.SupportsInt, + pnt: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> float: + """ + Intersect ray with hfield, return nearest distance or -1 if no intersection. + """ + +def mj_rayMesh( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + geomid: typing.SupportsInt, + pnt: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> float: + """ + Intersect ray with mesh, return nearest distance or -1 if no intersection. + """ + +def mj_referenceConstraint( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData +) -> None: + """ + Compute efc_vel, efc_aref. + """ + +def mj_resetCallbacks() -> None: + """ + Reset all callbacks to NULL pointers (NULL is the default). + """ + +def mj_resetData(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Reset data to defaults. + """ + +def mj_resetDataDebug( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, debug_value: typing.SupportsInt +) -> None: + """ + Reset data to defaults, fill everything else with debug_value. + """ + +def mj_resetDataKeyframe( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, key: typing.SupportsInt +) -> None: + """ + Reset data. If 0 <= key < nkey, set fields from specified keyframe. + """ + +def mj_rne( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + flg_acc: typing.SupportsInt, + result: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> None: + """ + RNE: compute M(qpos)*qacc + C(qpos,qvel); flg_acc=0 removes inertial term. + """ + +def mj_rnePostConstraint(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + RNE with complete data: compute cacc, cfrc_ext, cfrc_int. + """ + +def mj_saveLastXML(filename: str, m: mujoco._structs.MjModel) -> None: + """ + Update XML data structures with info from low-level model created with mj_loadXML, save as MJCF. If error is not NULL, it must have size error_sz. + """ + +def mj_saveModel( + m: mujoco._structs.MjModel, + filename: str | None = None, + buffer: typing.Annotated[ + numpy.typing.NDArray[numpy.uint8], "[m, 1]", "flags.writeable" + ] + | None = None, +) -> None: + """ + Save model to binary MJB file or memory buffer; buffer has precedence when given. + """ + +def mj_sensorAcc(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Evaluate acceleration and force-dependent sensors. + """ + +def mj_sensorPos(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Evaluate position-dependent sensors. + """ + +def mj_sensorVel(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Evaluate velocity-dependent sensors. + """ + +def mj_setConst(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Set constant fields of mjModel, corresponding to qpos0 configuration. + """ + +def mj_setKeyframe( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, k: typing.SupportsInt +) -> None: + """ + Copy current state to the k-th model keyframe. + """ + +def mj_setLengthRange( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + index: typing.SupportsInt, + opt: mujoco._structs.MjLROpt, +) -> None: + """ + Set actuator_lengthrange for specified actuator; return 1 if ok, 0 if error. + """ + +def mj_setState( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + state: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + sig: typing.SupportsInt, +) -> None: + """ + Set state. + """ + +def mj_setTotalmass(m: mujoco._structs.MjModel, newmass: typing.SupportsFloat) -> None: + """ + Scale body masses and inertias to achieve specified total mass. + """ + +def mj_sizeModel(m: mujoco._structs.MjModel) -> int: + """ + Return size of buffer needed to hold model. + """ + +def mj_solveM( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + x: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + y: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Solve linear system M * x = y using factorization: x = inv(L'*D*L)*y + """ + +def mj_solveM2( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + x: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + y: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + sqrtInvD: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Half of linear solve: x = sqrt(inv(D))*inv(L')*y + """ + +def mj_stateSize(m: mujoco._structs.MjModel, sig: typing.SupportsInt) -> int: + """ + Return size of state signature. + """ + +def mj_step( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, nstep: typing.SupportsInt = 1 +) -> None: + """ + Advance simulation, use control callback to obtain external force and control. Optionally, repeat nstep times. + """ + +def mj_step1(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Advance simulation in two steps: before external force and control is set by user. + """ + +def mj_step2(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Advance simulation in two steps: after external force and control is set by user. + """ + +def mj_subtreeVel(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Sub-tree linear velocity and angular momentum: compute subtree_linvel, subtree_angmom. + """ + +def mj_tendon(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute tendon lengths, velocities and moment arms. + """ + +def mj_transmission(m: mujoco._structs.MjModel, d: mujoco._structs.MjData) -> None: + """ + Compute actuator transmission lengths and moments. + """ + +def mj_version() -> int: + """ + Return version number: 1.0.2 is encoded as 102. + """ + +def mj_versionString() -> str: + """ + Return the current version of MuJoCo as a null-terminated string. + """ + +def mjd_inverseFD( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + eps: typing.SupportsFloat, + flg_actuation: typing.SupportsInt, + DfDq: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + DfDv: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + DfDa: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + DsDq: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + DsDv: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + DsDa: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + DmDq: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, +) -> None: + """ + Finite differenced Jacobians of (force, sensors) = mj_inverse(state, acceleration) All outputs are optional. Output dimensions (transposed w.r.t Control Theory convention): DfDq: (nv x nv) DfDv: (nv x nv) DfDa: (nv x nv) DsDq: (nv x nsensordata) DsDv: (nv x nsensordata) DsDa: (nv x nsensordata) DmDq: (nv x nM) single-letter shortcuts: inputs: q=qpos, v=qvel, a=qacc outputs: f=qfrc_inverse, s=sensordata, m=qM notes: optionally computes mass matrix Jacobian DmDq flg_actuation specifies whether to subtract qfrc_actuator from qfrc_inverse + """ + +def mjd_quatIntegrate( + vel: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + scale: typing.SupportsFloat, + Dquat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[9, 1]", "flags.writeable" + ], + Dvel: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[9, 1]", "flags.writeable" + ], + Dscale: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], +) -> None: + """ + Derivatives of mju_quatIntegrate. + """ + +def mjd_subQuat( + qa: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + qb: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + Da: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + Db: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, +) -> None: + """ + Derivatives of mju_subQuat. + """ + +def mjd_transitionFD( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + eps: typing.SupportsFloat, + flg_centered: typing.SupportsInt, + A: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + B: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + C: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, + D: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ] + | None, +) -> None: + """ + Finite differenced transition matrices (control theory notation) d(x_next) = A*dx + B*du d(sensor) = C*dx + D*du required output matrix dimensions: A: (2*nv+na x 2*nv+na) B: (2*nv+na x nu) D: (nsensordata x 2*nv+na) C: (nsensordata x nu) + """ + +def mju_Halton(index: typing.SupportsInt, base: typing.SupportsInt) -> float: + """ + Generate Halton sequence. + """ + +def mju_L1( + vec: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> float: + """ + Return L1 norm: sum(abs(vec)). + """ + +def mju_add( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Set res = vec1 + vec2. + """ + +def mju_add3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Set res = vec1 + vec2. + """ + +def mju_addScl( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + scl: typing.SupportsFloat, +) -> None: + """ + Set res = vec1 + vec2*scl. + """ + +def mju_addScl3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + scl: typing.SupportsFloat, +) -> None: + """ + Set res = vec1 + vec2*scl. + """ + +def mju_addTo( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Set res = res + vec. + """ + +def mju_addTo3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Set res = res + vec. + """ + +def mju_addToScl( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + scl: typing.SupportsFloat, +) -> None: + """ + Set res = res + vec*scl. + """ + +def mju_addToScl3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + scl: typing.SupportsFloat, +) -> None: + """ + Set res = res + vec*scl. + """ + +def mju_axisAngle2Quat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + axis: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + angle: typing.SupportsFloat, +) -> None: + """ + Convert axisAngle to quaternion. + """ + +def mju_band2Dense( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + ntotal: typing.SupportsInt, + nband: typing.SupportsInt, + ndense: typing.SupportsInt, + flg_sym: typing.SupportsInt, +) -> None: + """ + Convert banded matrix to dense matrix, fill upper triangle if flg_sym>0. + """ + +def mju_bandDiag( + i: typing.SupportsInt, + ntotal: typing.SupportsInt, + nband: typing.SupportsInt, + ndense: typing.SupportsInt, +) -> int: + """ + Address of diagonal element i in band-dense matrix representation. + """ + +def mju_bandMulMatVec( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + vec: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + ntotal: typing.SupportsInt, + nband: typing.SupportsInt, + ndense: typing.SupportsInt, + nvec: typing.SupportsInt, + flg_sym: typing.SupportsInt, +) -> None: + """ + Multiply band-diagonal matrix with nvec vectors, include upper triangle if flg_sym>0. + """ + +def mju_boxQP( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + R: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + index: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ] + | None, + H: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + g: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + lower: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"] | None, + upper: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"] | None, +) -> int: + """ + minimize 0.5*x'*H*x + x'*g s.t. lower <= x <= upper, return rank or -1 if failed inputs: n - problem dimension H - SPD matrix n*n g - bias vector n lower - lower bounds n upper - upper bounds n res - solution warmstart n return value: nfree <= n - rank of unconstrained subspace, -1 if failure outputs (required): res - solution n R - subspace Cholesky factor nfree*nfree allocated: n*(n+7) outputs (optional): index - set of free dimensions nfree allocated: n notes: the initial value of res is used to warmstart the solver R must have allocatd size n*(n+7), but only nfree*nfree values are used in output index (if given) must have allocated size n, but only nfree values are used in output only the lower triangles of H and R and are read from and written to, respectively the convenience function mju_boxQPmalloc allocates the required data structures + """ + +def mju_cholFactor( + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mindiag: typing.SupportsFloat, +) -> int: + """ + Cholesky decomposition: mat = L*L'; return rank, decomposition performed in-place into mat. + """ + +def mju_cholFactorBand( + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + ntotal: typing.SupportsInt, + nband: typing.SupportsInt, + ndense: typing.SupportsInt, + diagadd: typing.SupportsFloat, + diagmul: typing.SupportsFloat, +) -> float: + """ + Band-dense Cholesky decomposition. Returns minimum value in the factorized diagonal, or 0 if rank-deficient. mat has (ntotal-ndense) x nband + ndense x ntotal elements. The first (ntotal-ndense) x nband store the band part, left of diagonal, inclusive. The second ndense x ntotal store the band part as entire dense rows. Add diagadd+diagmul*mat_ii to diagonal before factorization. + """ + +def mju_cholSolve( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Solve (mat*mat') * res = vec, where mat is a Cholesky factor. + """ + +def mju_cholSolveBand( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + ntotal: typing.SupportsInt, + nband: typing.SupportsInt, + ndense: typing.SupportsInt, +) -> None: + """ + Solve (mat*mat')*res = vec where mat is a band-dense Cholesky factor. + """ + +def mju_cholUpdate( + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + x: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable"], + flg_plus: typing.SupportsInt, +) -> int: + """ + Cholesky rank-one update: L*L' +/- x*x'; return rank. + """ + +def mju_clip( + x: typing.SupportsFloat, min: typing.SupportsFloat, max: typing.SupportsFloat +) -> float: + """ + Clip x to the range [min, max]. + """ + +def mju_copy( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Set res = vec. + """ + +def mju_copy3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + data: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Set res = vec. + """ + +def mju_copy4( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + data: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Set res = vec. + """ + +def mju_cross( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + a: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + b: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Compute cross-product: res = cross(a, b). + """ + +def mju_d2n( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Convert from double to mjtNum. + """ + +def mju_decodePyramid( + force: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + pyramid: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + mu: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Convert pyramid representation to contact force. + """ + +def mju_dense2Band( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + ntotal: typing.SupportsInt, + nband: typing.SupportsInt, + ndense: typing.SupportsInt, +) -> None: + """ + Convert dense matrix to banded matrix. + """ + +def mju_dense2sparse( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + rownnz: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], + rowadr: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], + colind: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], +) -> int: + """ + Convert matrix from dense to sparse. nnz is size of res and colind, return 1 if too small, 0 otherwise. + """ + +def mju_derivQuat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + vel: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Compute time-derivative of quaternion, given 3D rotational velocity. + """ + +def mju_dist3( + pos1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + pos2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> float: + """ + Return Cartesian distance between 3D vectors pos1 and pos2. + """ + +def mju_dot( + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> float: + """ + Return dot-product of vec1 and vec2. + """ + +def mju_dot3( + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> float: + """ + Return dot-product of vec1 and vec2. + """ + +def mju_eig3( + eigval: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + eigvec: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[9, 1]", "flags.writeable" + ], + quat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], +) -> int: + """ + Eigenvalue decomposition of symmetric 3x3 matrix, mat = eigvec * diag(eigval) * eigvec'. + """ + +def mju_encodePyramid( + pyramid: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + force: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + mu: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Convert contact force to pyramid representation. + """ + +def mju_euler2Quat( + quat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + euler: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + seq: str, +) -> None: + """ + Convert sequence of Euler angles (radians) to quaternion. seq[0,1,2] must be in 'xyzXYZ', lower/upper-case mean intrinsic/extrinsic rotations. + """ + +def mju_eye( + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], +) -> None: + """ + Set mat to the identity matrix. + """ + +def mju_f2n( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[m, 1]"], +) -> None: + """ + Convert from float to mjtNum. + """ + +def mju_fill( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + val: typing.SupportsFloat, +) -> None: + """ + Set res = val. + """ + +def mju_insertionSort( + list: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> None: + """ + Insertion sort, resulting list is in increasing order. + """ + +def mju_insertionSortInt( + list: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[m, 1]", "flags.writeable" + ], +) -> None: + """ + Integer insertion sort, resulting list is in increasing order. + """ + +def mju_isBad(x: typing.SupportsFloat) -> int: + """ + Return 1 if nan or abs(x)>mjMAXVAL, 0 otherwise. Used by check functions. + """ + +def mju_isZero( + vec: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> int: + """ + Return 1 if all elements are 0. + """ + +def mju_mat2Quat( + quat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], +) -> None: + """ + Convert 3D rotation matrix to quaternion. + """ + +def mju_mat2Rot( + quat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], +) -> int: + """ + Extract 3D rotation from an arbitrary 3x3 matrix by refining the input quaternion. Returns the number of iterations required to converge + """ + +def mju_max(a: typing.SupportsFloat, b: typing.SupportsFloat) -> float: + """ + Return max(a,b) with single evaluation of a and b. + """ + +def mju_min(a: typing.SupportsFloat, b: typing.SupportsFloat) -> float: + """ + Return min(a,b) with single evaluation of a and b. + """ + +def mju_mulMatMat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat1: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + mat2: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Multiply matrices: res = mat1 * mat2. + """ + +def mju_mulMatMatT( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat1: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + mat2: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Multiply matrices, second argument transposed: res = mat1 * mat2'. + """ + +def mju_mulMatTMat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat1: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + mat2: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Multiply matrices, first argument transposed: res = mat1' * mat2. + """ + +def mju_mulMatTVec( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Multiply transposed matrix and vector: res = mat' * vec. + """ + +def mju_mulMatTVec3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Multiply transposed 3-by-3 matrix by vector: res = mat' * vec. + """ + +def mju_mulMatVec( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Multiply matrix and vector: res = mat * vec. + """ + +def mju_mulMatVec3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Multiply 3-by-3 matrix by vector: res = mat * vec. + """ + +def mju_mulPose( + posres: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + quatres: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + pos1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + quat1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + pos2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + quat2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Multiply two poses. + """ + +def mju_mulQuat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + quat1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + quat2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Multiply quaternions. + """ + +def mju_mulQuatAxis( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + axis: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Multiply quaternion and axis. + """ + +def mju_mulVecMatVec( + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> float: + """ + Multiply square matrix with vectors on both sides: returns vec1' * mat * vec2. + """ + +def mju_muscleBias( + len: typing.SupportsFloat, + lengthrange: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"], + acc0: typing.SupportsFloat, + prm: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], +) -> float: + """ + Muscle passive force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax). + """ + +def mju_muscleDynamics( + ctrl: typing.SupportsFloat, + act: typing.SupportsFloat, + prm: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> float: + """ + Muscle activation dynamics, prm = (tau_act, tau_deact, smoothing_width). + """ + +def mju_muscleGain( + len: typing.SupportsFloat, + vel: typing.SupportsFloat, + lengthrange: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"], + acc0: typing.SupportsFloat, + prm: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], +) -> float: + """ + Muscle active force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax). + """ + +def mju_n2d( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Convert from mjtNum to double. + """ + +def mju_n2f( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float32], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Convert from mjtNum to float. + """ + +def mju_negPose( + posres: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + quatres: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + pos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Conjugate pose, corresponding to the opposite spatial transformation. + """ + +def mju_negQuat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Conjugate quaternion, corresponding to opposite rotation. + """ + +def mju_norm( + res: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> float: + """ + Return vector length (without normalizing vector). + """ + +def mju_norm3( + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> float: + """ + Return vector length (without normalizing the vector). + """ + +def mju_normalize( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> float: + """ + Normalize vector, return length before normalization. + """ + +def mju_normalize3( + vec: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], +) -> float: + """ + Normalize vector, return length before normalization. + """ + +def mju_normalize4( + vec: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], +) -> float: + """ + Normalize vector, return length before normalization. + """ + +def mju_printMat( + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Print matrix to screen. + """ + +def mju_printMatSparse( + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + rownnz: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[m, 1]"], + rowadr: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[m, 1]"], + colind: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[m, 1]"], +) -> None: + """ + Print sparse matrix to screen. + """ + +def mju_quat2Mat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[9, 1]", "flags.writeable" + ], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Convert quaternion to 3D rotation matrix. + """ + +def mju_quat2Vel( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + dt: typing.SupportsFloat, +) -> None: + """ + Convert quaternion (corresponding to orientation difference) to 3D velocity. + """ + +def mju_quatIntegrate( + quat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + vel: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + scale: typing.SupportsFloat, +) -> None: + """ + Integrate quaternion given 3D angular velocity. + """ + +def mju_quatZ2Vec( + quat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Construct quaternion performing rotation from z-axis to given vector. + """ + +def mju_rayFlex( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + flex_layer: typing.SupportsInt, + flg_vert: typing.SupportsInt, + flg_edge: typing.SupportsInt, + flg_face: typing.SupportsInt, + flg_skin: typing.SupportsInt, + flexid: typing.SupportsInt, + pnt: typing.SupportsFloat, + vec: typing.SupportsFloat, + vertid: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[1, 1]", "flags.writeable" + ], +) -> float: + """ + Intersect ray with flex, return nearest distance or -1 if no intersection, and also output nearest vertex id. + """ + +def mju_rayGeom( + pos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], + size: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + pnt: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + geomtype: typing.SupportsInt, +) -> float: + """ + Intersect ray with pure geom, return nearest distance or -1 if no intersection. + """ + +def mju_raySkin( + nface: typing.SupportsInt, + nvert: typing.SupportsInt, + face: typing.SupportsInt, + vert: typing.SupportsFloat, + pnt: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vertid: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[1, 1]", "flags.writeable" + ], +) -> float: + """ + Intersect ray with skin, return nearest distance or -1 if no intersection, and also output nearest vertex id. + """ + +def mju_rotVecQuat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Rotate vector by quaternion. + """ + +def mju_round(x: typing.SupportsFloat) -> int: + """ + Round x to nearest integer. + """ + +def mju_scl( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + scl: typing.SupportsFloat, +) -> None: + """ + Set res = vec*scl. + """ + +def mju_scl3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + scl: typing.SupportsFloat, +) -> None: + """ + Set res = vec*scl. + """ + +def mju_sigmoid(x: typing.SupportsFloat) -> float: + """ + Sigmoid function over 0<=x<=1 using quintic polynomial. + """ + +def mju_sign(x: typing.SupportsFloat) -> float: + """ + Return sign of x: +1, -1 or 0. + """ + +def mju_sparse2dense( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + rownnz: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[m, 1]"], + rowadr: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[m, 1]"], + colind: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[m, 1]"], +) -> None: + """ + Convert matrix from sparse to dense. + """ + +def mju_springDamper( + pos0: typing.SupportsFloat, + vel0: typing.SupportsFloat, + Kp: typing.SupportsFloat, + Kv: typing.SupportsFloat, + dt: typing.SupportsFloat, +) -> float: + """ + Integrate spring-damper analytically, return pos(dt). + """ + +def mju_sqrMatTD( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], + diag: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ] + | None, +) -> None: + """ + Set res = mat' * diag * mat if diag is not NULL, and res = mat' * mat otherwise. + """ + +def mju_standardNormal(num2: typing.SupportsFloat | None) -> float: + """ + Standard normal random number generator (optional second number). + """ + +def mju_str2Type(str: str) -> int: + """ + Convert type name to type id (mjtObj). + """ + +def mju_sub( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Set res = vec1 - vec2. + """ + +def mju_sub3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + vec2: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Set res = vec1 - vec2. + """ + +def mju_subFrom( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[m, 1]"], +) -> None: + """ + Set res = res - vec. + """ + +def mju_subFrom3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Set res = res - vec. + """ + +def mju_subQuat( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + qa: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + qb: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], +) -> None: + """ + Subtract quaternions, express as 3D velocity: qb*quat(res) = qa. + """ + +def mju_sum( + vec: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> float: + """ + Return sum(vec). + """ + +def mju_symmetrize( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Symmetrize square matrix res = (mat + mat')/2. + """ + +def mju_transformSpatial( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]"], + flg_force: typing.SupportsInt, + newpos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + oldpos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + rotnew2old: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], +) -> None: + """ + Coordinate transform of 6D motion or force vector in rotation:translation format. rotnew2old is 3-by-3, NULL means no rotation; flg_force specifies force or motion type. + """ + +def mju_transpose( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], + "[m, n]", + "flags.writeable", + "flags.c_contiguous", + ], + mat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, n]", "flags.c_contiguous" + ], +) -> None: + """ + Transpose matrix: res = mat'. + """ + +def mju_trnVecPose( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + pos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + quat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Transform vector by pose. + """ + +def mju_type2Str(type: typing.SupportsInt) -> str: + """ + Convert type id (mjtObj) to type name. + """ + +def mju_unit4( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], +) -> None: + """ + Set res = (1,0,0,0). + """ + +def mju_warningText(warning: typing.SupportsInt, info: typing.SupportsInt) -> str: + """ + Construct a warning message given the warning type and info. + """ + +def mju_writeLog(type: str, msg: str) -> None: + """ + Write [datetime, type: message] to MUJOCO_LOG.TXT. + """ + +def mju_writeNumBytes(nbytes: typing.SupportsInt) -> str: + """ + Return human readable number of bytes using standard letter suffix. + """ + +def mju_zero( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[m, 1]", "flags.writeable" + ], +) -> None: + """ + Set res = 0. + """ + +def mju_zero3( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], +) -> None: + """ + Set res = 0. + """ + +def mju_zero4( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], +) -> None: + """ + Set res = 0. + """ + +def mjv_addGeoms( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + opt: mujoco._structs.MjvOption, + pert: mujoco._structs.MjvPerturb, + catmask: typing.SupportsInt, + scn: mujoco._structs.MjvScene, +) -> None: + """ + Add geoms from selected categories. + """ + +def mjv_alignToCamera( + res: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + vec: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + forward: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Rotate 3D vec in horizontal plane by angle between (0,1) and (forward_x,forward_y). + """ + +def mjv_applyPerturbForce( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + pert: mujoco._structs.MjvPerturb, +) -> None: + """ + Set perturb force,torque in d->xfrc_applied, if selected body is dynamic. + """ + +def mjv_applyPerturbPose( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + pert: mujoco._structs.MjvPerturb, + flg_paused: typing.SupportsInt, +) -> None: + """ + Set perturb pos,quat in d->mocap when selected body is mocap, and in d->qpos otherwise. Write d->qpos only if flg_paused and subtree root for selected body has free joint. + """ + +def mjv_cameraInModel( + headpos: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + forward: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + up: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + scn: mujoco._structs.MjvScene, +) -> None: + """ + Get camera info in model space; average left and right OpenGL cameras. + """ + +def mjv_cameraInRoom( + headpos: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + forward: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + up: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + scn: mujoco._structs.MjvScene, +) -> None: + """ + Get camera info in room space; average left and right OpenGL cameras. + """ + +def mjv_connector( + geom: mujoco._structs.MjvGeom, + type: typing.SupportsInt, + width: typing.SupportsFloat, + from_: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + to: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], +) -> None: + """ + Set (type, size, pos, mat) for connector-type geom between given points. Assume that mjv_initGeom was already called to set all other properties. Width of mjGEOM_LINE is denominated in pixels. + """ + +def mjv_defaultCamera(cam: mujoco._structs.MjvCamera) -> None: + """ + Set default camera. + """ + +def mjv_defaultFigure(fig: mujoco._structs.MjvFigure) -> None: + """ + Set default figure. + """ + +def mjv_defaultFreeCamera( + m: mujoco._structs.MjModel, cam: mujoco._structs.MjvCamera +) -> None: + """ + Set default free camera. + """ + +def mjv_defaultOption(opt: mujoco._structs.MjvOption) -> None: + """ + Set default visualization options. + """ + +def mjv_defaultPerturb(pert: mujoco._structs.MjvPerturb) -> None: + """ + Set default perturbation. + """ + +def mjv_frustumHeight(scn: mujoco._structs.MjvScene) -> float: + """ + Get frustum height at unit distance from camera; average left and right OpenGL cameras. + """ + +def mjv_initGeom( + geom: mujoco._structs.MjvGeom, + type: typing.SupportsInt, + size: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + pos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + mat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[9, 1]"], + rgba: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"], +) -> None: + """ + Initialize given geom fields when not NULL, set the rest to their default values. + """ + +def mjv_initPerturb( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + scn: mujoco._structs.MjvScene, + pert: mujoco._structs.MjvPerturb, +) -> None: + """ + Copy perturb pos,quat from selected body; set scale for perturbation. + """ + +def mjv_makeLights( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, scn: mujoco._structs.MjvScene +) -> None: + """ + Make list of lights. + """ + +def mjv_model2room( + roompos: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + roomquat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + modelpos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + modelquat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + scn: mujoco._structs.MjvScene, +) -> None: + """ + Transform pose from model to room space. + """ + +def mjv_moveCamera( + m: mujoco._structs.MjModel, + action: typing.SupportsInt, + reldx: typing.SupportsFloat, + reldy: typing.SupportsFloat, + scn: mujoco._structs.MjvScene, + cam: mujoco._structs.MjvCamera, +) -> None: + """ + Move camera with mouse; action is mjtMouse. + """ + +def mjv_moveModel( + m: mujoco._structs.MjModel, + action: typing.SupportsInt, + reldx: typing.SupportsFloat, + reldy: typing.SupportsFloat, + roomup: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + scn: mujoco._structs.MjvScene, +) -> None: + """ + Move model with mouse; action is mjtMouse. + """ + +def mjv_movePerturb( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + action: typing.SupportsInt, + reldx: typing.SupportsFloat, + reldy: typing.SupportsFloat, + scn: mujoco._structs.MjvScene, + pert: mujoco._structs.MjvPerturb, +) -> None: + """ + Move perturb object with mouse; action is mjtMouse. + """ + +def mjv_room2model( + modelpos: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + modelquat: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable" + ], + roompos: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"], + roomquat: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"], + scn: mujoco._structs.MjvScene, +) -> None: + """ + Transform pose from room to model space. + """ + +def mjv_select( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + vopt: mujoco._structs.MjvOption, + aspectratio: typing.SupportsFloat, + relx: typing.SupportsFloat, + rely: typing.SupportsFloat, + scn: mujoco._structs.MjvScene, + selpnt: typing.Annotated[ + numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable" + ], + geomid: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[1, 1]", "flags.writeable" + ], + flexid: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[1, 1]", "flags.writeable" + ], + skinid: typing.Annotated[ + numpy.typing.NDArray[numpy.int32], "[1, 1]", "flags.writeable" + ], +) -> int: + """ + Select geom, flex or skin with mouse, return bodyid; -1: none selected. + """ + +def mjv_updateCamera( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + cam: mujoco._structs.MjvCamera, + scn: mujoco._structs.MjvScene, +) -> None: + """ + Update camera. + """ + +def mjv_updateScene( + m: mujoco._structs.MjModel, + d: mujoco._structs.MjData, + opt: mujoco._structs.MjvOption, + pert: mujoco._structs.MjvPerturb | None, + cam: mujoco._structs.MjvCamera, + catmask: typing.SupportsInt, + scn: mujoco._structs.MjvScene, +) -> None: + """ + Update entire scene given model state. + """ + +def mjv_updateSkin( + m: mujoco._structs.MjModel, d: mujoco._structs.MjData, scn: mujoco._structs.MjvScene +) -> None: + """ + Update skins. + """ diff --git a/typings/mujoco/_render.pyi b/typings/mujoco/_render.pyi new file mode 100644 index 000000000..a94fad06e --- /dev/null +++ b/typings/mujoco/_render.pyi @@ -0,0 +1,500 @@ +from __future__ import annotations +import mujoco._structs +import numpy +import numpy.typing +import typing + +__all__: list[str] = [ + "MjrContext", + "MjrRect", + "mjr_addAux", + "mjr_blitAux", + "mjr_blitBuffer", + "mjr_changeFont", + "mjr_drawPixels", + "mjr_figure", + "mjr_findRect", + "mjr_finish", + "mjr_getError", + "mjr_label", + "mjr_maxViewport", + "mjr_overlay", + "mjr_readPixels", + "mjr_rectangle", + "mjr_render", + "mjr_resizeOffscreen", + "mjr_restoreBuffer", + "mjr_setAux", + "mjr_setBuffer", + "mjr_text", + "mjr_uploadHField", + "mjr_uploadMesh", + "mjr_uploadTexture", +] + +class MjrContext: + @typing.overload + def __init__(self) -> None: ... + @typing.overload + def __init__( + self, arg0: mujoco._structs.MjModel, arg1: typing.SupportsInt + ) -> None: ... + def free(self) -> None: + """ + Frees resources in current active OpenGL context, sets struct to default. + """ + @property + def auxColor(self) -> numpy.typing.NDArray[numpy.uint32]: ... + @auxColor.setter + def auxColor(self, arg1: typing.Any) -> None: ... + @property + def auxColor_r(self) -> numpy.typing.NDArray[numpy.uint32]: ... + @auxColor_r.setter + def auxColor_r(self, arg1: typing.Any) -> None: ... + @property + def auxFBO(self) -> numpy.typing.NDArray[numpy.uint32]: ... + @auxFBO.setter + def auxFBO(self, arg1: typing.Any) -> None: ... + @property + def auxFBO_r(self) -> numpy.typing.NDArray[numpy.uint32]: ... + @auxFBO_r.setter + def auxFBO_r(self, arg1: typing.Any) -> None: ... + @property + def auxHeight(self) -> numpy.typing.NDArray[numpy.int32]: ... + @auxHeight.setter + def auxHeight(self, arg1: typing.Any) -> None: ... + @property + def auxSamples(self) -> numpy.typing.NDArray[numpy.int32]: ... + @auxSamples.setter + def auxSamples(self, arg1: typing.Any) -> None: ... + @property + def auxWidth(self) -> numpy.typing.NDArray[numpy.int32]: ... + @auxWidth.setter + def auxWidth(self, arg1: typing.Any) -> None: ... + @property + def baseBuiltin(self) -> int: ... + @baseBuiltin.setter + def baseBuiltin(self, arg1: typing.SupportsFloat) -> None: ... + @property + def baseFontBig(self) -> int: ... + @baseFontBig.setter + def baseFontBig(self, arg1: typing.SupportsFloat) -> None: ... + @property + def baseFontNormal(self) -> int: ... + @baseFontNormal.setter + def baseFontNormal(self, arg1: typing.SupportsFloat) -> None: ... + @property + def baseFontShadow(self) -> int: ... + @baseFontShadow.setter + def baseFontShadow(self, arg1: typing.SupportsFloat) -> None: ... + @property + def baseHField(self) -> int: ... + @baseHField.setter + def baseHField(self, arg1: typing.SupportsFloat) -> None: ... + @property + def baseMesh(self) -> int: ... + @baseMesh.setter + def baseMesh(self, arg1: typing.SupportsFloat) -> None: ... + @property + def basePlane(self) -> int: ... + @basePlane.setter + def basePlane(self, arg1: typing.SupportsFloat) -> None: ... + @property + def charHeight(self) -> int: ... + @charHeight.setter + def charHeight(self, arg1: typing.SupportsFloat) -> None: ... + @property + def charHeightBig(self) -> int: ... + @charHeightBig.setter + def charHeightBig(self, arg1: typing.SupportsFloat) -> None: ... + @property + def charWidth(self) -> numpy.typing.NDArray[numpy.int32]: ... + @charWidth.setter + def charWidth(self, arg1: typing.Any) -> None: ... + @property + def charWidthBig(self) -> numpy.typing.NDArray[numpy.int32]: ... + @charWidthBig.setter + def charWidthBig(self, arg1: typing.Any) -> None: ... + @property + def currentBuffer(self) -> int: ... + @currentBuffer.setter + def currentBuffer(self, arg1: typing.SupportsFloat) -> None: ... + @property + def fogEnd(self) -> float: ... + @fogEnd.setter + def fogEnd(self, arg1: typing.SupportsFloat) -> None: ... + @property + def fogRGBA(self) -> numpy.typing.NDArray[numpy.float32]: ... + @fogRGBA.setter + def fogRGBA(self, arg1: typing.Any) -> None: ... + @property + def fogStart(self) -> float: ... + @fogStart.setter + def fogStart(self, arg1: typing.SupportsFloat) -> None: ... + @property + def fontScale(self) -> int: ... + @fontScale.setter + def fontScale(self, arg1: typing.SupportsFloat) -> None: ... + @property + def glInitialized(self) -> int: ... + @glInitialized.setter + def glInitialized(self, arg1: typing.SupportsFloat) -> None: ... + @property + def lineWidth(self) -> float: ... + @lineWidth.setter + def lineWidth(self, arg1: typing.SupportsFloat) -> None: ... + @property + def mat_texid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mat_texid.setter + def mat_texid(self, arg1: typing.Any) -> None: ... + @property + def mat_texrepeat(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_texrepeat.setter + def mat_texrepeat(self, arg1: typing.Any) -> None: ... + @property + def mat_texuniform(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mat_texuniform.setter + def mat_texuniform(self, arg1: typing.Any) -> None: ... + @property + def nskin(self) -> int: ... + @property + def ntexture(self) -> int: ... + @ntexture.setter + def ntexture(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offColor(self) -> int: ... + @offColor.setter + def offColor(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offColor_r(self) -> int: ... + @offColor_r.setter + def offColor_r(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offDepthStencil(self) -> int: ... + @offDepthStencil.setter + def offDepthStencil(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offDepthStencil_r(self) -> int: ... + @offDepthStencil_r.setter + def offDepthStencil_r(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offFBO(self) -> int: ... + @offFBO.setter + def offFBO(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offFBO_r(self) -> int: ... + @offFBO_r.setter + def offFBO_r(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offHeight(self) -> int: ... + @offHeight.setter + def offHeight(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offSamples(self) -> int: ... + @offSamples.setter + def offSamples(self, arg1: typing.SupportsFloat) -> None: ... + @property + def offWidth(self) -> int: ... + @offWidth.setter + def offWidth(self, arg1: typing.SupportsFloat) -> None: ... + @property + def rangeBuiltin(self) -> int: ... + @rangeBuiltin.setter + def rangeBuiltin(self, arg1: typing.SupportsFloat) -> None: ... + @property + def rangeFont(self) -> int: ... + @rangeFont.setter + def rangeFont(self, arg1: typing.SupportsFloat) -> None: ... + @property + def rangeHField(self) -> int: ... + @rangeHField.setter + def rangeHField(self, arg1: typing.SupportsFloat) -> None: ... + @property + def rangeMesh(self) -> int: ... + @rangeMesh.setter + def rangeMesh(self, arg1: typing.SupportsFloat) -> None: ... + @property + def rangePlane(self) -> int: ... + @rangePlane.setter + def rangePlane(self, arg1: typing.SupportsFloat) -> None: ... + @property + def readDepthMap(self) -> int: ... + @readDepthMap.setter + def readDepthMap(self, arg1: typing.SupportsFloat) -> None: ... + @property + def readPixelFormat(self) -> int: ... + @readPixelFormat.setter + def readPixelFormat(self, arg1: typing.SupportsFloat) -> None: ... + @property + def shadowClip(self) -> float: ... + @shadowClip.setter + def shadowClip(self, arg1: typing.SupportsFloat) -> None: ... + @property + def shadowFBO(self) -> int: ... + @shadowFBO.setter + def shadowFBO(self, arg1: typing.SupportsFloat) -> None: ... + @property + def shadowScale(self) -> float: ... + @shadowScale.setter + def shadowScale(self, arg1: typing.SupportsFloat) -> None: ... + @property + def shadowSize(self) -> int: ... + @shadowSize.setter + def shadowSize(self, arg1: typing.SupportsFloat) -> None: ... + @property + def shadowTex(self) -> int: ... + @shadowTex.setter + def shadowTex(self, arg1: typing.SupportsFloat) -> None: ... + @property + def skinfaceVBO(self) -> tuple: ... + @property + def skinnormalVBO(self) -> tuple: ... + @property + def skintexcoordVBO(self) -> tuple: ... + @property + def skinvertVBO(self) -> tuple: ... + @property + def texture(self) -> numpy.typing.NDArray[numpy.uint32]: ... + @texture.setter + def texture(self, arg1: typing.Any) -> None: ... + @property + def textureType(self) -> numpy.typing.NDArray[numpy.int32]: ... + @textureType.setter + def textureType(self, arg1: typing.Any) -> None: ... + @property + def windowAvailable(self) -> int: ... + @windowAvailable.setter + def windowAvailable(self, arg1: typing.SupportsFloat) -> None: ... + @property + def windowDoublebuffer(self) -> int: ... + @windowDoublebuffer.setter + def windowDoublebuffer(self, arg1: typing.SupportsFloat) -> None: ... + @property + def windowSamples(self) -> int: ... + @windowSamples.setter + def windowSamples(self, arg1: typing.SupportsFloat) -> None: ... + @property + def windowStereo(self) -> int: ... + @windowStereo.setter + def windowStereo(self, arg1: typing.SupportsFloat) -> None: ... + +class MjrRect: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjrRect: ... + def __deepcopy__(self, arg0: dict) -> MjrRect: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__( + self, + left: typing.SupportsInt, + bottom: typing.SupportsInt, + width: typing.SupportsInt, + height: typing.SupportsInt, + ) -> None: ... + def __repr__(self) -> str: ... + @property + def bottom(self) -> int: ... + @bottom.setter + def bottom(self, arg0: typing.SupportsInt) -> None: ... + @property + def height(self) -> int: ... + @height.setter + def height(self, arg0: typing.SupportsInt) -> None: ... + @property + def left(self) -> int: ... + @left.setter + def left(self, arg0: typing.SupportsInt) -> None: ... + @property + def width(self) -> int: ... + @width.setter + def width(self, arg0: typing.SupportsInt) -> None: ... + +def mjr_addAux( + index: typing.SupportsInt, + width: typing.SupportsInt, + height: typing.SupportsInt, + samples: typing.SupportsInt, + con: MjrContext, +) -> None: + """ + Add Aux buffer with given index to context; free previous Aux buffer. + """ + +def mjr_blitAux( + index: typing.SupportsInt, + src: MjrRect, + left: typing.SupportsInt, + bottom: typing.SupportsInt, + con: MjrContext, +) -> None: + """ + Blit from Aux buffer to con->currentBuffer. + """ + +def mjr_blitBuffer( + src: MjrRect, + dst: MjrRect, + flg_color: typing.SupportsInt, + flg_depth: typing.SupportsInt, + con: MjrContext, +) -> None: + """ + Blit from src viewpoint in current framebuffer to dst viewport in other framebuffer. If src, dst have different size and flg_depth==0, color is interpolated with GL_LINEAR. + """ + +def mjr_changeFont(fontscale: typing.SupportsInt, con: MjrContext) -> None: + """ + Change font of existing context. + """ + +def mjr_drawPixels( + rgb: typing.Annotated[numpy.typing.NDArray[numpy.uint8], "[m, 1]"] | None, + depth: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[m, 1]"] | None, + viewport: MjrRect, + con: MjrContext, +) -> None: + """ + Draw pixels from client buffer to current OpenGL framebuffer. Viewport is in OpenGL framebuffer; client buffer starts at (0,0). + """ + +def mjr_figure( + viewport: MjrRect, fig: mujoco._structs.MjvFigure, con: MjrContext +) -> None: + """ + Draw 2D figure. + """ + +def mjr_findRect( + x: typing.SupportsInt, y: typing.SupportsInt, nrect: typing.SupportsInt, rect: MjrRect +) -> int: + """ + Find first rectangle containing mouse, -1: not found. + """ + +def mjr_finish() -> None: + """ + Call glFinish. + """ + +def mjr_getError() -> int: + """ + Call glGetError and return result. + """ + +def mjr_label( + viewport: MjrRect, + font: typing.SupportsInt, + txt: str, + r: typing.SupportsFloat, + g: typing.SupportsFloat, + b: typing.SupportsFloat, + a: typing.SupportsFloat, + rt: typing.SupportsFloat, + gt: typing.SupportsFloat, + bt: typing.SupportsFloat, + con: MjrContext, +) -> None: + """ + Draw rectangle with centered text. + """ + +def mjr_maxViewport(con: MjrContext) -> MjrRect: + """ + Get maximum viewport for active buffer. + """ + +def mjr_overlay( + font: typing.SupportsInt, + gridpos: typing.SupportsInt, + viewport: MjrRect, + overlay: str, + overlay2: str, + con: MjrContext, +) -> None: + """ + Draw text overlay; font is mjtFont; gridpos is mjtGridPos. + """ + +def mjr_readPixels( + rgb: typing.Annotated[numpy.typing.ArrayLike, numpy.uint8] | None, + depth: typing.Annotated[numpy.typing.ArrayLike, numpy.float32] | None, + viewport: MjrRect, + con: MjrContext, +) -> None: + """ + Read pixels from current OpenGL framebuffer to client buffer. Viewport is in OpenGL framebuffer; client buffer starts at (0,0). + """ + +def mjr_rectangle( + viewport: MjrRect, + r: typing.SupportsFloat, + g: typing.SupportsFloat, + b: typing.SupportsFloat, + a: typing.SupportsFloat, +) -> None: + """ + Draw rectangle. + """ + +def mjr_render( + viewport: MjrRect, scn: mujoco._structs.MjvScene, con: MjrContext +) -> None: + """ + Render 3D scene. + """ + +def mjr_resizeOffscreen( + width: typing.SupportsInt, height: typing.SupportsInt, con: MjrContext +) -> None: + """ + Resize offscreen buffers. + """ + +def mjr_restoreBuffer(con: MjrContext) -> None: + """ + Make con->currentBuffer current again. + """ + +def mjr_setAux(index: typing.SupportsInt, con: MjrContext) -> None: + """ + Set Aux buffer for custom OpenGL rendering (call restoreBuffer when done). + """ + +def mjr_setBuffer(framebuffer: typing.SupportsInt, con: MjrContext) -> None: + """ + Set OpenGL framebuffer for rendering: mjFB_WINDOW or mjFB_OFFSCREEN. If only one buffer is available, set that buffer and ignore framebuffer argument. + """ + +def mjr_text( + font: typing.SupportsInt, + txt: str, + con: MjrContext, + x: typing.SupportsFloat, + y: typing.SupportsFloat, + r: typing.SupportsFloat, + g: typing.SupportsFloat, + b: typing.SupportsFloat, +) -> None: + """ + Draw text at (x,y) in relative coordinates; font is mjtFont. + """ + +def mjr_uploadHField( + m: mujoco._structs.MjModel, con: MjrContext, hfieldid: typing.SupportsInt +) -> None: + """ + Upload height field to GPU, overwriting previous upload if any. + """ + +def mjr_uploadMesh( + m: mujoco._structs.MjModel, con: MjrContext, meshid: typing.SupportsInt +) -> None: + """ + Upload mesh to GPU, overwriting previous upload if any. + """ + +def mjr_uploadTexture( + m: mujoco._structs.MjModel, con: MjrContext, texid: typing.SupportsInt +) -> None: + """ + Upload texture to GPU, overwriting previous upload if any. + """ diff --git a/typings/mujoco/_specs.pyi b/typings/mujoco/_specs.pyi new file mode 100644 index 000000000..cddfa2251 --- /dev/null +++ b/typings/mujoco/_specs.pyi @@ -0,0 +1,2937 @@ +from __future__ import annotations +import collections.abc +import mujoco._enums +import mujoco._structs +import numpy +import numpy.typing +import typing +__all__: list[str] = ['MjByteVec', 'MjCharVec', 'MjDoubleVec', 'MjFloatVec', 'MjIntVec', 'MjOption', 'MjSpec', 'MjStatistic', 'MjStringVec', 'MjVisual', 'MjVisualHeadlight', 'MjVisualRgba', 'MjsActuator', 'MjsBody', 'MjsCamera', 'MjsCompiler', 'MjsDefault', 'MjsElement', 'MjsEquality', 'MjsExclude', 'MjsFlex', 'MjsFrame', 'MjsGeom', 'MjsHField', 'MjsJoint', 'MjsKey', 'MjsLight', 'MjsMaterial', 'MjsMesh', 'MjsNumeric', 'MjsOrientation', 'MjsPair', 'MjsPlugin', 'MjsSensor', 'MjsSite', 'MjsSkin', 'MjsTendon', 'MjsText', 'MjsTexture', 'MjsTuple', 'MjsWrap'] +class MjByteVec: + def __getitem__(self, arg0: typing.SupportsInt) -> ...: + ... + def __init__(self, arg0: ..., arg1: typing.SupportsInt) -> None: + ... + def __iter__(self) -> collections.abc.Iterator[...]: + ... + def __len__(self) -> int: + ... + def __setitem__(self, arg0: typing.SupportsInt, arg1: ...) -> None: + ... +class MjCharVec: + def __getitem__(self, arg0: typing.SupportsInt) -> str: + ... + def __init__(self, arg0: str, arg1: typing.SupportsInt) -> None: + ... + def __iter__(self) -> collections.abc.Iterator[str]: + ... + def __len__(self) -> int: + ... + def __setitem__(self, arg0: typing.SupportsInt, arg1: str) -> None: + ... +class MjDoubleVec: + def __getitem__(self, arg0: typing.SupportsInt) -> float: + ... + def __init__(self, arg0: typing.SupportsFloat, arg1: typing.SupportsInt) -> None: + ... + def __iter__(self) -> collections.abc.Iterator[float]: + ... + def __len__(self) -> int: + ... + def __setitem__(self, arg0: typing.SupportsInt, arg1: typing.SupportsFloat) -> None: + ... +class MjFloatVec: + def __getitem__(self, arg0: typing.SupportsInt) -> float: + ... + def __init__(self, arg0: typing.SupportsFloat, arg1: typing.SupportsInt) -> None: + ... + def __iter__(self) -> collections.abc.Iterator[float]: + ... + def __len__(self) -> int: + ... + def __setitem__(self, arg0: typing.SupportsInt, arg1: typing.SupportsFloat) -> None: + ... +class MjIntVec: + def __getitem__(self, arg0: typing.SupportsInt) -> int: + ... + def __init__(self, arg0: typing.SupportsInt, arg1: typing.SupportsInt) -> None: + ... + def __iter__(self) -> collections.abc.Iterator[int]: + ... + def __len__(self) -> int: + ... + def __setitem__(self, arg0: typing.SupportsInt, arg1: typing.SupportsInt) -> None: + ... +class MjOption: + @property + def apirate(self) -> float: + ... + @apirate.setter + def apirate(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def ccd_iterations(self) -> int: + ... + @ccd_iterations.setter + def ccd_iterations(self, arg1: typing.SupportsInt) -> None: + ... + @property + def ccd_tolerance(self) -> float: + ... + @ccd_tolerance.setter + def ccd_tolerance(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def cone(self) -> int: + ... + @cone.setter + def cone(self, arg1: typing.SupportsInt) -> None: + ... + @property + def density(self) -> float: + ... + @density.setter + def density(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def disableactuator(self) -> int: + ... + @disableactuator.setter + def disableactuator(self, arg1: typing.SupportsInt) -> None: + ... + @property + def disableflags(self) -> int: + ... + @disableflags.setter + def disableflags(self, arg1: typing.SupportsInt) -> None: + ... + @property + def enableflags(self) -> int: + ... + @enableflags.setter + def enableflags(self, arg1: typing.SupportsInt) -> None: + ... + @property + def gravity(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @gravity.setter + def gravity(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def impratio(self) -> float: + ... + @impratio.setter + def impratio(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def integrator(self) -> int: + ... + @integrator.setter + def integrator(self, arg1: typing.SupportsInt) -> None: + ... + @property + def iterations(self) -> int: + ... + @iterations.setter + def iterations(self, arg1: typing.SupportsInt) -> None: + ... + @property + def jacobian(self) -> int: + ... + @jacobian.setter + def jacobian(self, arg1: typing.SupportsInt) -> None: + ... + @property + def ls_iterations(self) -> int: + ... + @ls_iterations.setter + def ls_iterations(self, arg1: typing.SupportsInt) -> None: + ... + @property + def ls_tolerance(self) -> float: + ... + @ls_tolerance.setter + def ls_tolerance(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def magnetic(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @magnetic.setter + def magnetic(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def noslip_iterations(self) -> int: + ... + @noslip_iterations.setter + def noslip_iterations(self, arg1: typing.SupportsInt) -> None: + ... + @property + def noslip_tolerance(self) -> float: + ... + @noslip_tolerance.setter + def noslip_tolerance(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def o_friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @o_friction.setter + def o_friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def o_margin(self) -> float: + ... + @o_margin.setter + def o_margin(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def o_solimp(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @o_solimp.setter + def o_solimp(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def o_solref(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @o_solref.setter + def o_solref(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def sdf_initpoints(self) -> int: + ... + @sdf_initpoints.setter + def sdf_initpoints(self, arg1: typing.SupportsInt) -> None: + ... + @property + def sdf_iterations(self) -> int: + ... + @sdf_iterations.setter + def sdf_iterations(self, arg1: typing.SupportsInt) -> None: + ... + @property + def solver(self) -> int: + ... + @solver.setter + def solver(self, arg1: typing.SupportsInt) -> None: + ... + @property + def timestep(self) -> float: + ... + @timestep.setter + def timestep(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def tolerance(self) -> float: + ... + @tolerance.setter + def tolerance(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def viscosity(self) -> float: + ... + @viscosity.setter + def viscosity(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def wind(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @wind.setter + def wind(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... +class MjSpec: + assets: dict + comment: str + compiler: MjsCompiler + meshdir: str + modelfiledir: str + modelname: str + option: MjOption + override_assets: bool + stat: MjStatistic + texturedir: str + visual: MjVisual + @staticmethod + def from_file(filename: str, include: collections.abc.Mapping[str, bytes] | None = None, assets: dict | None = None) -> MjSpec: + """ + Creates a spec from an XML file. + + Parameters + ---------- + filename : str + Path to the XML file. + include : dict, optional + A dictionary of xml files included by the model. The keys are file names + and the values are file contents. + assets : dict, optional + A dictionary of assets to be used by the spec. The keys are asset names + and the values are asset contents. + """ + @staticmethod + def from_string(xml: str, include: collections.abc.Mapping[str, bytes] | None = None, assets: dict | None = None) -> MjSpec: + """ + Creates a spec from an XML string. + + Parameters + ---------- + xml : str + XML string. + include : dict, optional + A dictionary of xml files included by the model. The keys are file names + and the values are file contents. + assets : dict, optional + A dictionary of assets to be used by the spec. The keys are asset names + and the values are asset contents. + """ + @staticmethod + def from_zip(file: typing.Union[str, typing.IO[bytes]]) -> MjSpec: + """ + Reads a zip file and returns an MjSpec. + + Args: + file: The path to the file to read from or the file object to read from. + Returns: + An MjSpec object. + """ + @staticmethod + def resolve_orientation(degree: bool, sequence: MjCharVec = None, orientation: MjsOrientation) -> typing.Annotated[list[float], "FixedSize(4)"]: + ... + @staticmethod + def to_zip(spec: MjSpec, file: typing.Union[str, typing.IO[bytes]]) -> None: + """ + Converts an MjSpec to a zip file. + + Args: + spec: The mjSpec to save to a file. + file: The path to the file to save to or the file object to write to. + """ + def __init__(self) -> None: + ... + def activate_plugin(self, name: str) -> None: + ... + def actuator(self, arg0: str) -> MjsActuator: + ... + def add_actuator(self, default: MjsDefault = None, **kwargs) -> MjsActuator: + ... + def add_default(self, arg0: str, arg1: MjsDefault) -> MjsDefault: + ... + def add_equality(self, default: MjsDefault = None, **kwargs) -> MjsEquality: + ... + def add_exclude(self, **kwargs) -> MjsExclude: + ... + def add_flex(self, **kwargs) -> MjsFlex: + ... + def add_hfield(self, **kwargs) -> MjsHField: + ... + def add_key(self, **kwargs) -> MjsKey: + ... + def add_material(self, default: MjsDefault = None, **kwargs) -> MjsMaterial: + ... + def add_mesh(self, default: MjsDefault = None, **kwargs) -> MjsMesh: + ... + def add_numeric(self, **kwargs) -> MjsNumeric: + ... + def add_pair(self, default: MjsDefault = None, **kwargs) -> MjsPair: + ... + def add_plugin(self, **kwargs) -> MjsPlugin: + ... + def add_sensor(self, **kwargs) -> MjsSensor: + ... + def add_skin(self, **kwargs) -> MjsSkin: + ... + def add_tendon(self, default: MjsDefault = None, **kwargs) -> MjsTendon: + ... + def add_text(self, **kwargs) -> MjsText: + ... + def add_texture(self, **kwargs) -> MjsTexture: + ... + def add_tuple(self, **kwargs) -> MjsTuple: + ... + def attach(self, child: MjSpec, prefix: str | None = None, suffix: str | None = None, site: typing.Any | None = None, frame: typing.Any | None = None) -> MjsFrame: + ... + def body(self, arg0: str) -> MjsBody: + ... + def camera(self, arg0: str) -> MjsCamera: + ... + def compile(self) -> typing.Any: + ... + def copy(self) -> MjSpec: + ... + @typing.overload + def delete(self, arg0: MjsDefault) -> None: + ... + @typing.overload + def delete(self, arg0: MjsBody) -> None: + ... + @typing.overload + def delete(self, arg0: MjsFrame) -> None: + ... + @typing.overload + def delete(self, arg0: MjsGeom) -> None: + ... + @typing.overload + def delete(self, arg0: MjsJoint) -> None: + ... + @typing.overload + def delete(self, arg0: MjsSite) -> None: + ... + @typing.overload + def delete(self, arg0: MjsCamera) -> None: + ... + @typing.overload + def delete(self, arg0: MjsLight) -> None: + ... + @typing.overload + def delete(self, arg0: MjsMaterial) -> None: + ... + @typing.overload + def delete(self, arg0: MjsMesh) -> None: + ... + @typing.overload + def delete(self, arg0: MjsPair) -> None: + ... + @typing.overload + def delete(self, arg0: MjsEquality) -> None: + ... + @typing.overload + def delete(self, arg0: MjsActuator) -> None: + ... + @typing.overload + def delete(self, arg0: MjsTendon) -> None: + ... + @typing.overload + def delete(self, arg0: MjsSensor) -> None: + ... + @typing.overload + def delete(self, arg0: MjsFlex) -> None: + ... + @typing.overload + def delete(self, arg0: MjsHField) -> None: + ... + @typing.overload + def delete(self, arg0: MjsSkin) -> None: + ... + @typing.overload + def delete(self, arg0: MjsTexture) -> None: + ... + @typing.overload + def delete(self, arg0: MjsKey) -> None: + ... + @typing.overload + def delete(self, arg0: MjsText) -> None: + ... + @typing.overload + def delete(self, arg0: MjsNumeric) -> None: + ... + @typing.overload + def delete(self, arg0: MjsExclude) -> None: + ... + @typing.overload + def delete(self, arg0: MjsTuple) -> None: + ... + @typing.overload + def delete(self, arg0: MjsPlugin) -> None: + ... + def equality(self, arg0: str) -> MjsEquality: + ... + def exclude(self, arg0: str) -> MjsExclude: + ... + def find_default(self, arg0: str) -> MjsDefault: + ... + def flex(self, arg0: str) -> MjsFlex: + ... + def frame(self, arg0: str) -> MjsFrame: + ... + def geom(self, arg0: str) -> MjsGeom: + ... + def hfield(self, arg0: str) -> MjsHField: + ... + def joint(self, arg0: str) -> MjsJoint: + ... + def key(self, arg0: str) -> MjsKey: + ... + def light(self, arg0: str) -> MjsLight: + ... + def material(self, arg0: str) -> MjsMaterial: + ... + def mesh(self, arg0: str) -> MjsMesh: + ... + def numeric(self, arg0: str) -> MjsNumeric: + ... + def pair(self, arg0: str) -> MjsPair: + ... + def plugin(self, arg0: str) -> MjsPlugin: + ... + def recompile(self, arg0: typing.Any, arg1: typing.Any) -> typing.Any: + ... + def sensor(self, arg0: str) -> MjsSensor: + ... + def site(self, arg0: str) -> MjsSite: + ... + def skin(self, arg0: str) -> MjsSkin: + ... + def tendon(self, arg0: str) -> MjsTendon: + ... + def text(self, arg0: str) -> MjsText: + ... + def texture(self, arg0: str) -> MjsTexture: + ... + def to_file(self, arg0: str) -> None: + ... + def to_xml(self) -> str: + ... + def tuple(self, arg0: str) -> MjsTuple: + ... + @property + def _address(self) -> int: + ... + @property + def actuators(self) -> list: + ... + @property + def bodies(self) -> list: + ... + @property + def cameras(self) -> list: + ... + @property + def copy_during_attach(self) -> None: + ... + @copy_during_attach.setter + def copy_during_attach(self, arg1: bool) -> int: + ... + @property + def default(self) -> MjsDefault: + ... + @property + def equalities(self) -> list: + ... + @property + def excludes(self) -> list: + ... + @property + def flexes(self) -> list: + ... + @property + def frames(self) -> list: + ... + @property + def geoms(self) -> list: + ... + @property + def hasImplicitPluginElem(self) -> int: + ... + @hasImplicitPluginElem.setter + def hasImplicitPluginElem(self, arg1: typing.SupportsInt) -> None: + ... + @property + def hfields(self) -> list: + ... + @property + def joints(self) -> list: + ... + @property + def keys(self) -> list: + ... + @property + def lights(self) -> list: + ... + @property + def materials(self) -> list: + ... + @property + def memory(self) -> int: + ... + @memory.setter + def memory(self, arg1: typing.SupportsInt) -> None: + ... + @property + def meshes(self) -> list: + ... + @property + def nconmax(self) -> int: + ... + @nconmax.setter + def nconmax(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nemax(self) -> int: + ... + @nemax.setter + def nemax(self, arg1: typing.SupportsInt) -> None: + ... + @property + def njmax(self) -> int: + ... + @njmax.setter + def njmax(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nkey(self) -> int: + ... + @nkey.setter + def nkey(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nstack(self) -> int: + ... + @nstack.setter + def nstack(self, arg1: typing.SupportsInt) -> None: + ... + @property + def numerics(self) -> list: + ... + @property + def nuser_actuator(self) -> int: + ... + @nuser_actuator.setter + def nuser_actuator(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuser_body(self) -> int: + ... + @nuser_body.setter + def nuser_body(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuser_cam(self) -> int: + ... + @nuser_cam.setter + def nuser_cam(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuser_geom(self) -> int: + ... + @nuser_geom.setter + def nuser_geom(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuser_jnt(self) -> int: + ... + @nuser_jnt.setter + def nuser_jnt(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuser_sensor(self) -> int: + ... + @nuser_sensor.setter + def nuser_sensor(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuser_site(self) -> int: + ... + @nuser_site.setter + def nuser_site(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuser_tendon(self) -> int: + ... + @nuser_tendon.setter + def nuser_tendon(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nuserdata(self) -> int: + ... + @nuserdata.setter + def nuserdata(self, arg1: typing.SupportsInt) -> None: + ... + @property + def pairs(self) -> list: + ... + @property + def parent(self) -> MjSpec: + ... + @property + def plugins(self) -> list: + ... + @property + def sensors(self) -> list: + ... + @property + def sites(self) -> list: + ... + @property + def skins(self) -> list: + ... + @property + def strippath(self) -> int: + ... + @strippath.setter + def strippath(self, arg1: typing.SupportsInt) -> None: + ... + @property + def tendons(self) -> list: + ... + @property + def texts(self) -> list: + ... + @property + def textures(self) -> list: + ... + @property + def tuples(self) -> list: + ... + @property + def worldbody(self) -> MjsBody: + ... +class MjStatistic: + @property + def center(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @center.setter + def center(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def extent(self) -> float: + ... + @extent.setter + def extent(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def meaninertia(self) -> float: + ... + @meaninertia.setter + def meaninertia(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def meanmass(self) -> float: + ... + @meanmass.setter + def meanmass(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def meansize(self) -> float: + ... + @meansize.setter + def meansize(self, arg1: typing.SupportsFloat) -> None: + ... +class MjStringVec: + def __getitem__(self, arg0: typing.SupportsInt) -> str: + ... + def __init__(self, arg0: str, arg1: typing.SupportsInt) -> None: + ... + def __iter__(self) -> collections.abc.Iterator[str]: + ... + def __len__(self) -> int: + ... + def __setitem__(self, arg0: typing.SupportsInt, arg1: str) -> None: + ... +class MjVisual: + global: mujoco._structs.MjVisual.Global + global_: mujoco._structs.MjVisual.Global + headlight: MjVisualHeadlight + map: mujoco._structs.MjVisual.Map + quality: mujoco._structs.MjVisual.Quality + rgba: MjVisualRgba + scale: mujoco._structs.MjVisual.Scale +class MjVisualHeadlight: + @property + def active(self) -> int: + ... + @active.setter + def active(self, arg1: typing.SupportsInt) -> None: + ... + @property + def ambient(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]", "flags.writeable"]: + ... + @ambient.setter + def ambient(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]"]) -> None: + ... + @property + def diffuse(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]", "flags.writeable"]: + ... + @diffuse.setter + def diffuse(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]"]) -> None: + ... + @property + def specular(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]", "flags.writeable"]: + ... + @specular.setter + def specular(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]"]) -> None: + ... +class MjVisualRgba: + @property + def actuator(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @actuator.setter + def actuator(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def actuatornegative(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @actuatornegative.setter + def actuatornegative(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def actuatorpositive(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @actuatorpositive.setter + def actuatorpositive(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def bv(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @bv.setter + def bv(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def bvactive(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @bvactive.setter + def bvactive(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def camera(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @camera.setter + def camera(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def com(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @com.setter + def com(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def connect(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @connect.setter + def connect(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def constraint(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @constraint.setter + def constraint(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def contactforce(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @contactforce.setter + def contactforce(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def contactfriction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @contactfriction.setter + def contactfriction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def contactgap(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @contactgap.setter + def contactgap(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def contactpoint(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @contactpoint.setter + def contactpoint(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def contacttorque(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @contacttorque.setter + def contacttorque(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def crankbroken(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @crankbroken.setter + def crankbroken(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def fog(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @fog.setter + def fog(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def force(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @force.setter + def force(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def frustum(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @frustum.setter + def frustum(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def haze(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @haze.setter + def haze(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def inertia(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @inertia.setter + def inertia(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def joint(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @joint.setter + def joint(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def light(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @light.setter + def light(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def rangefinder(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @rangefinder.setter + def rangefinder(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def selectpoint(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @selectpoint.setter + def selectpoint(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def slidercrank(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @slidercrank.setter + def slidercrank(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... +class MjsActuator: + biastype: mujoco._enums.mjtBias + classname: MjsDefault + dyntype: mujoco._enums.mjtDyn + gaintype: mujoco._enums.mjtGain + info: str + name: str + plugin: MjsPlugin + refsite: str + slidersite: str + target: str + trntype: mujoco._enums.mjtTrn + def set_to_adhesion(self, gain: typing.SupportsFloat) -> None: + ... + def set_to_cylinder(self, timeconst: typing.SupportsFloat, bias: typing.SupportsFloat, area: typing.SupportsFloat, diameter: typing.SupportsFloat = -1) -> None: + ... + def set_to_damper(self, kv: typing.SupportsFloat) -> None: + ... + def set_to_intvelocity(self, kp: typing.SupportsFloat, kv: typing.SupportsFloat = -1, dampratio: typing.SupportsFloat = -1, timeconst: typing.SupportsFloat = -1, inheritrange: bool = False) -> None: + ... + def set_to_motor(self) -> None: + ... + def set_to_muscle(self, timeconst: typing.SupportsFloat = -1, tausmooth: typing.SupportsFloat, range: typing.SupportsFloat = [-1.0, -1.0], force: typing.SupportsFloat = -1, scale: typing.SupportsFloat = -1, lmin: typing.SupportsFloat = -1, lmax: typing.SupportsFloat = -1, vmax: typing.SupportsFloat = -1, fpmax: typing.SupportsFloat = -1, fvmax: typing.SupportsFloat = -1) -> None: + ... + def set_to_position(self, kp: typing.SupportsFloat, kv: typing.SupportsFloat = -1, dampratio: typing.SupportsFloat = -1, timeconst: typing.SupportsFloat = -1, inheritrange: bool = False) -> None: + ... + def set_to_velocity(self, kv: typing.SupportsFloat) -> None: + ... + @property + def actdim(self) -> int: + ... + @actdim.setter + def actdim(self, arg1: typing.SupportsInt) -> None: + ... + @property + def actearly(self) -> int: + ... + @actearly.setter + def actearly(self, arg1: typing.SupportsInt) -> None: + ... + @property + def actlimited(self) -> int: + ... + @actlimited.setter + def actlimited(self, arg1: typing.SupportsInt) -> None: + ... + @property + def actrange(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @actrange.setter + def actrange(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def biasprm(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[10, 1]", "flags.writeable"]: + ... + @biasprm.setter + def biasprm(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[10, 1]"]) -> None: + ... + @property + def cranklength(self) -> float: + ... + @cranklength.setter + def cranklength(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def ctrllimited(self) -> int: + ... + @ctrllimited.setter + def ctrllimited(self, arg1: typing.SupportsInt) -> None: + ... + @property + def ctrlrange(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @ctrlrange.setter + def ctrlrange(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def dynprm(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[10, 1]", "flags.writeable"]: + ... + @dynprm.setter + def dynprm(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[10, 1]"]) -> None: + ... + @property + def forcelimited(self) -> int: + ... + @forcelimited.setter + def forcelimited(self, arg1: typing.SupportsInt) -> None: + ... + @property + def forcerange(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @forcerange.setter + def forcerange(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def gainprm(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[10, 1]", "flags.writeable"]: + ... + @gainprm.setter + def gainprm(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[10, 1]"]) -> None: + ... + @property + def gear(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable"]: + ... + @gear.setter + def gear(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]"]) -> None: + ... + @property + def group(self) -> int: + ... + @group.setter + def group(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def inheritrange(self) -> float: + ... + @inheritrange.setter + def inheritrange(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def lengthrange(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @lengthrange.setter + def lengthrange(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsBody: + alt: MjsOrientation + childclass: str + classname: MjsDefault + ialt: MjsOrientation + info: str + name: str + plugin: MjsPlugin + def add_body(self, default: MjsDefault = None, **kwargs) -> MjsBody: + ... + def add_camera(self, default: MjsDefault = None, **kwargs) -> MjsCamera: + ... + def add_frame(self, default: MjsFrame = None, **kwargs) -> MjsFrame: + ... + def add_freejoint(self, **kwargs) -> MjsJoint: + ... + def add_geom(self, default: MjsDefault = None, **kwargs) -> MjsGeom: + ... + def add_joint(self, default: MjsDefault = None, **kwargs) -> MjsJoint: + ... + def add_light(self, default: MjsDefault = None, **kwargs) -> MjsLight: + ... + def add_site(self, default: MjsDefault = None, **kwargs) -> MjsSite: + ... + def attach_frame(self, frame: MjsFrame, prefix: str | None = None, suffix: str | None = None) -> MjsFrame: + ... + @typing.overload + def find_all(self, arg0: mujoco._enums.mjtObj) -> list: + ... + @typing.overload + def find_all(self, arg0: str) -> list: + ... + def find_child(self, arg0: str) -> MjsBody: + ... + def first_body(self) -> MjsBody: + ... + def first_camera(self) -> MjsCamera: + ... + def first_frame(self) -> MjsFrame: + ... + def first_geom(self) -> MjsGeom: + ... + def first_joint(self) -> MjsJoint: + ... + def first_light(self) -> MjsLight: + ... + def first_site(self) -> MjsSite: + ... + def next_body(self, arg0: MjsBody) -> MjsBody: + ... + def next_camera(self, arg0: MjsCamera) -> MjsCamera: + ... + def next_frame(self, arg0: MjsFrame) -> MjsFrame: + ... + def next_geom(self, arg0: MjsGeom) -> MjsGeom: + ... + def next_joint(self, arg0: MjsJoint) -> MjsJoint: + ... + def next_light(self, arg0: MjsLight) -> MjsLight: + ... + def next_site(self, arg0: MjsSite) -> MjsSite: + ... + def set_frame(self, arg0: MjsFrame) -> None: + ... + def to_frame(self) -> MjsFrame: + ... + @property + def bodies(self) -> list: + ... + @property + def cameras(self) -> list: + ... + @property + def explicitinertial(self) -> int: + ... + @explicitinertial.setter + def explicitinertial(self, arg1: typing.SupportsInt) -> None: + ... + @property + def frame(self) -> MjsFrame: + ... + @property + def frames(self) -> list: + ... + @property + def fullinertia(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable"]: + ... + @fullinertia.setter + def fullinertia(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]"]) -> None: + ... + @property + def geoms(self) -> list: + ... + @property + def gravcomp(self) -> float: + ... + @gravcomp.setter + def gravcomp(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def id(self) -> int: + ... + @property + def inertia(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @inertia.setter + def inertia(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def ipos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @ipos.setter + def ipos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def iquat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @iquat.setter + def iquat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def joints(self) -> list: + ... + @property + def lights(self) -> list: + ... + @property + def mass(self) -> float: + ... + @mass.setter + def mass(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def mocap(self) -> int: + ... + @mocap.setter + def mocap(self, arg1: typing.SupportsInt) -> None: + ... + @property + def parent(self) -> MjsBody: + ... + @property + def pos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @pos.setter + def pos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def quat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @quat.setter + def quat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def sites(self) -> list: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsCamera: + alt: MjsOrientation + classname: MjsDefault + info: str + mode: mujoco._enums.mjtCamLight + name: str + targetbody: str + def set_frame(self, arg0: MjsFrame) -> None: + ... + @property + def focal_length(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]", "flags.writeable"]: + ... + @focal_length.setter + def focal_length(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]"]) -> None: + ... + @property + def focal_pixel(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]", "flags.writeable"]: + ... + @focal_pixel.setter + def focal_pixel(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]"]) -> None: + ... + @property + def fovy(self) -> float: + ... + @fovy.setter + def fovy(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def frame(self) -> MjsFrame: + ... + @property + def id(self) -> int: + ... + @property + def intrinsic(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @intrinsic.setter + def intrinsic(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def ipd(self) -> float: + ... + @ipd.setter + def ipd(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def orthographic(self) -> int: + ... + @orthographic.setter + def orthographic(self, arg1: typing.SupportsInt) -> None: + ... + @property + def parent(self) -> MjsBody: + ... + @property + def pos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @pos.setter + def pos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def principal_length(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]", "flags.writeable"]: + ... + @principal_length.setter + def principal_length(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]"]) -> None: + ... + @property + def principal_pixel(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]", "flags.writeable"]: + ... + @principal_pixel.setter + def principal_pixel(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]"]) -> None: + ... + @property + def quat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @quat.setter + def quat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def resolution(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]", "flags.writeable"]: + ... + @resolution.setter + def resolution(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]"]) -> None: + ... + @property + def sensor_size(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]", "flags.writeable"]: + ... + @sensor_size.setter + def sensor_size(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsCompiler: + LRopt: mujoco._structs.MjLROpt + @property + def alignfree(self) -> int: + ... + @alignfree.setter + def alignfree(self, arg1: typing.SupportsInt) -> None: + ... + @property + def autolimits(self) -> int: + ... + @autolimits.setter + def autolimits(self, arg1: typing.SupportsInt) -> None: + ... + @property + def balanceinertia(self) -> int: + ... + @balanceinertia.setter + def balanceinertia(self, arg1: typing.SupportsInt) -> None: + ... + @property + def boundinertia(self) -> float: + ... + @boundinertia.setter + def boundinertia(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def boundmass(self) -> float: + ... + @boundmass.setter + def boundmass(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def degree(self) -> int: + ... + @degree.setter + def degree(self, arg1: typing.SupportsInt) -> None: + ... + @property + def discardvisual(self) -> int: + ... + @discardvisual.setter + def discardvisual(self, arg1: typing.SupportsInt) -> None: + ... + @property + def eulerseq(self) -> MjCharVec: + ... + @eulerseq.setter + def eulerseq(self, arg1: typing.Any) -> None: + ... + @property + def fitaabb(self) -> int: + ... + @fitaabb.setter + def fitaabb(self, arg1: typing.SupportsInt) -> None: + ... + @property + def fusestatic(self) -> int: + ... + @fusestatic.setter + def fusestatic(self, arg1: typing.SupportsInt) -> None: + ... + @property + def inertiafromgeom(self) -> int: + ... + @inertiafromgeom.setter + def inertiafromgeom(self, arg1: typing.SupportsInt) -> None: + ... + @property + def inertiagrouprange(self) -> typing.Annotated[numpy.typing.NDArray[numpy.int32], "[2, 1]", "flags.writeable"]: + ... + @inertiagrouprange.setter + def inertiagrouprange(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[2, 1]"]) -> None: + ... + @property + def saveinertial(self) -> int: + ... + @saveinertial.setter + def saveinertial(self, arg1: typing.SupportsInt) -> None: + ... + @property + def settotalmass(self) -> float: + ... + @settotalmass.setter + def settotalmass(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def usethread(self) -> int: + ... + @usethread.setter + def usethread(self, arg1: typing.SupportsInt) -> None: + ... +class MjsDefault: + actuator: MjsActuator + camera: MjsCamera + equality: MjsEquality + flex: MjsFlex + geom: MjsGeom + joint: MjsJoint + light: MjsLight + material: MjsMaterial + mesh: MjsMesh + name: str + pair: MjsPair + site: MjsSite + tendon: MjsTendon +class MjsElement: + pass +class MjsEquality: + classname: MjsDefault + info: str + name: str + name1: str + name2: str + objtype: mujoco._enums.mjtObj + type: mujoco._enums.mjtEq + @property + def active(self) -> int: + ... + @active.setter + def active(self, arg1: typing.SupportsInt) -> None: + ... + @property + def data(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[11, 1]", "flags.writeable"]: + ... + @data.setter + def data(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[11, 1]"]) -> None: + ... + @property + def id(self) -> int: + ... + @property + def signature(self) -> int: + ... + @property + def solimp(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp.setter + def solimp(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solref(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref.setter + def solref(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... +class MjsExclude: + bodyname1: str + bodyname2: str + info: str + name: str + @property + def id(self) -> int: + ... + @property + def signature(self) -> int: + ... +class MjsFlex: + info: str + material: str + name: str + @property + def activelayers(self) -> int: + ... + @activelayers.setter + def activelayers(self, arg1: typing.SupportsInt) -> None: + ... + @property + def conaffinity(self) -> int: + ... + @conaffinity.setter + def conaffinity(self, arg1: typing.SupportsInt) -> None: + ... + @property + def condim(self) -> int: + ... + @condim.setter + def condim(self, arg1: typing.SupportsInt) -> None: + ... + @property + def contype(self) -> int: + ... + @contype.setter + def contype(self, arg1: typing.SupportsInt) -> None: + ... + @property + def damping(self) -> float: + ... + @damping.setter + def damping(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def dim(self) -> int: + ... + @dim.setter + def dim(self, arg1: typing.SupportsInt) -> None: + ... + @property + def edgedamping(self) -> float: + ... + @edgedamping.setter + def edgedamping(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def edgestiffness(self) -> float: + ... + @edgestiffness.setter + def edgestiffness(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def elastic2d(self) -> int: + ... + @elastic2d.setter + def elastic2d(self, arg1: typing.SupportsInt) -> None: + ... + @property + def elem(self) -> MjIntVec: + ... + @elem.setter + def elem(self, arg1: typing.Any) -> None: + ... + @property + def elemtexcoord(self) -> MjIntVec: + ... + @elemtexcoord.setter + def elemtexcoord(self, arg1: typing.Any) -> None: + ... + @property + def flatskin(self) -> int: + ... + @flatskin.setter + def flatskin(self, arg1: typing.SupportsInt) -> None: + ... + @property + def friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @friction.setter + def friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def gap(self) -> float: + ... + @gap.setter + def gap(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def group(self) -> int: + ... + @group.setter + def group(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def internal(self) -> int: + ... + @internal.setter + def internal(self, arg1: typing.SupportsInt) -> None: + ... + @property + def margin(self) -> float: + ... + @margin.setter + def margin(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def node(self) -> MjDoubleVec: + ... + @node.setter + def node(self, arg1: typing.Any) -> None: + ... + @property + def nodebody(self) -> MjStringVec: + ... + @nodebody.setter + def nodebody(self, arg1: typing.Any) -> None: + ... + @property + def poisson(self) -> float: + ... + @poisson.setter + def poisson(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def priority(self) -> int: + ... + @priority.setter + def priority(self, arg1: typing.SupportsInt) -> None: + ... + @property + def radius(self) -> float: + ... + @radius.setter + def radius(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def rgba(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @rgba.setter + def rgba(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def selfcollide(self) -> int: + ... + @selfcollide.setter + def selfcollide(self, arg1: typing.SupportsInt) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def solimp(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp.setter + def solimp(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solmix(self) -> float: + ... + @solmix.setter + def solmix(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def solref(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref.setter + def solref(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def texcoord(self) -> MjFloatVec: + ... + @texcoord.setter + def texcoord(self, arg1: typing.Any) -> None: + ... + @property + def thickness(self) -> float: + ... + @thickness.setter + def thickness(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def vert(self) -> MjDoubleVec: + ... + @vert.setter + def vert(self, arg1: typing.Any) -> None: + ... + @property + def vertbody(self) -> MjStringVec: + ... + @vertbody.setter + def vertbody(self, arg1: typing.Any) -> None: + ... + @property + def vertcollide(self) -> int: + ... + @vertcollide.setter + def vertcollide(self, arg1: typing.SupportsInt) -> None: + ... + @property + def young(self) -> float: + ... + @young.setter + def young(self, arg1: typing.SupportsFloat) -> None: + ... +class MjsFrame: + alt: MjsOrientation + childclass: str + info: str + name: str + def attach_body(self, body: MjsBody, prefix: str | None = None, suffix: str | None = None) -> MjsBody: + ... + def set_frame(self, arg0: MjsFrame) -> None: + ... + @property + def frame(self) -> MjsFrame: + ... + @property + def id(self) -> int: + ... + @property + def parent(self) -> MjsBody: + ... + @property + def pos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @pos.setter + def pos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def quat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @quat.setter + def quat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... +class MjsGeom: + alt: MjsOrientation + classname: MjsDefault + hfieldname: str + info: str + material: str + meshname: str + name: str + plugin: MjsPlugin + type: mujoco._enums.mjtGeom + typeinertia: mujoco._enums.mjtGeomInertia + def set_frame(self, arg0: MjsFrame) -> None: + ... + @property + def conaffinity(self) -> int: + ... + @conaffinity.setter + def conaffinity(self, arg1: typing.SupportsInt) -> None: + ... + @property + def condim(self) -> int: + ... + @condim.setter + def condim(self, arg1: typing.SupportsInt) -> None: + ... + @property + def contype(self) -> int: + ... + @contype.setter + def contype(self, arg1: typing.SupportsInt) -> None: + ... + @property + def density(self) -> float: + ... + @density.setter + def density(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def fitscale(self) -> float: + ... + @fitscale.setter + def fitscale(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def fluid_coefs(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @fluid_coefs.setter + def fluid_coefs(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def fluid_ellipsoid(self) -> float: + ... + @fluid_ellipsoid.setter + def fluid_ellipsoid(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def frame(self) -> MjsFrame: + ... + @property + def friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @friction.setter + def friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def fromto(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable"]: + ... + @fromto.setter + def fromto(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]"]) -> None: + ... + @property + def gap(self) -> float: + ... + @gap.setter + def gap(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def group(self) -> int: + ... + @group.setter + def group(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def margin(self) -> float: + ... + @margin.setter + def margin(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def mass(self) -> float: + ... + @mass.setter + def mass(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def parent(self) -> MjsBody: + ... + @property + def pos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @pos.setter + def pos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def priority(self) -> int: + ... + @priority.setter + def priority(self, arg1: typing.SupportsInt) -> None: + ... + @property + def quat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @quat.setter + def quat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def rgba(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @rgba.setter + def rgba(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def size(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @size.setter + def size(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def solimp(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp.setter + def solimp(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solmix(self) -> float: + ... + @solmix.setter + def solmix(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def solref(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref.setter + def solref(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsHField: + content_type: str + file: str + info: str + name: str + @property + def id(self) -> int: + ... + @property + def ncol(self) -> int: + ... + @ncol.setter + def ncol(self, arg1: typing.SupportsInt) -> None: + ... + @property + def nrow(self) -> int: + ... + @nrow.setter + def nrow(self, arg1: typing.SupportsInt) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def size(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @size.setter + def size(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def userdata(self) -> MjFloatVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsJoint: + classname: MjsDefault + info: str + name: str + type: mujoco._enums.mjtJoint + def set_frame(self, arg0: MjsFrame) -> None: + ... + @property + def actfrclimited(self) -> int: + ... + @actfrclimited.setter + def actfrclimited(self, arg1: typing.SupportsInt) -> None: + ... + @property + def actfrcrange(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @actfrcrange.setter + def actfrcrange(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def actgravcomp(self) -> int: + ... + @actgravcomp.setter + def actgravcomp(self, arg1: typing.SupportsInt) -> None: + ... + @property + def align(self) -> int: + ... + @align.setter + def align(self, arg1: typing.SupportsInt) -> None: + ... + @property + def armature(self) -> float: + ... + @armature.setter + def armature(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def axis(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @axis.setter + def axis(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def damping(self) -> float: + ... + @damping.setter + def damping(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def frame(self) -> MjsFrame: + ... + @property + def frictionloss(self) -> float: + ... + @frictionloss.setter + def frictionloss(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def group(self) -> int: + ... + @group.setter + def group(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def limited(self) -> int: + ... + @limited.setter + def limited(self, arg1: typing.SupportsInt) -> None: + ... + @property + def margin(self) -> float: + ... + @margin.setter + def margin(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def parent(self) -> MjsBody: + ... + @property + def pos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @pos.setter + def pos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def range(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @range.setter + def range(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def ref(self) -> float: + ... + @ref.setter + def ref(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def solimp_friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp_friction.setter + def solimp_friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solimp_limit(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp_limit.setter + def solimp_limit(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solref_friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref_friction.setter + def solref_friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def solref_limit(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref_limit.setter + def solref_limit(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def springdamper(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @springdamper.setter + def springdamper(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def springref(self) -> float: + ... + @springref.setter + def springref(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def stiffness(self) -> float: + ... + @stiffness.setter + def stiffness(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsKey: + info: str + name: str + @property + def act(self) -> MjDoubleVec: + ... + @act.setter + def act(self, arg1: typing.Any) -> None: + ... + @property + def ctrl(self) -> MjDoubleVec: + ... + @ctrl.setter + def ctrl(self, arg1: typing.Any) -> None: + ... + @property + def id(self) -> int: + ... + @property + def mpos(self) -> MjDoubleVec: + ... + @mpos.setter + def mpos(self, arg1: typing.Any) -> None: + ... + @property + def mquat(self) -> MjDoubleVec: + ... + @mquat.setter + def mquat(self, arg1: typing.Any) -> None: + ... + @property + def qpos(self) -> MjDoubleVec: + ... + @qpos.setter + def qpos(self, arg1: typing.Any) -> None: + ... + @property + def qvel(self) -> MjDoubleVec: + ... + @qvel.setter + def qvel(self, arg1: typing.Any) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def time(self) -> float: + ... + @time.setter + def time(self, arg1: typing.SupportsFloat) -> None: + ... +class MjsLight: + classname: MjsDefault + info: str + mode: mujoco._enums.mjtCamLight + name: str + targetbody: str + texture: str + type: mujoco._enums.mjtLightType + def set_frame(self, arg0: MjsFrame) -> None: + ... + @property + def active(self) -> int: + ... + @active.setter + def active(self, arg1: typing.SupportsInt) -> None: + ... + @property + def ambient(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]", "flags.writeable"]: + ... + @ambient.setter + def ambient(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]"]) -> None: + ... + @property + def attenuation(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]", "flags.writeable"]: + ... + @attenuation.setter + def attenuation(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]"]) -> None: + ... + @property + def bulbradius(self) -> float: + ... + @bulbradius.setter + def bulbradius(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def castshadow(self) -> int: + ... + @castshadow.setter + def castshadow(self, arg1: typing.SupportsInt) -> None: + ... + @property + def cutoff(self) -> float: + ... + @cutoff.setter + def cutoff(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def diffuse(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]", "flags.writeable"]: + ... + @diffuse.setter + def diffuse(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]"]) -> None: + ... + @property + def dir(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @dir.setter + def dir(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def exponent(self) -> float: + ... + @exponent.setter + def exponent(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def frame(self) -> MjsFrame: + ... + @property + def id(self) -> int: + ... + @property + def intensity(self) -> float: + ... + @intensity.setter + def intensity(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def parent(self) -> MjsBody: + ... + @property + def pos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @pos.setter + def pos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def range(self) -> float: + ... + @range.setter + def range(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def specular(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]", "flags.writeable"]: + ... + @specular.setter + def specular(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[3, 1]"]) -> None: + ... +class MjsMaterial: + classname: MjsDefault + info: str + name: str + @property + def emission(self) -> float: + ... + @emission.setter + def emission(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def id(self) -> int: + ... + @property + def metallic(self) -> float: + ... + @metallic.setter + def metallic(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def reflectance(self) -> float: + ... + @reflectance.setter + def reflectance(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def rgba(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @rgba.setter + def rgba(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def roughness(self) -> float: + ... + @roughness.setter + def roughness(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def shininess(self) -> float: + ... + @shininess.setter + def shininess(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def specular(self) -> float: + ... + @specular.setter + def specular(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def texrepeat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]", "flags.writeable"]: + ... + @texrepeat.setter + def texrepeat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[2, 1]"]) -> None: + ... + @property + def textures(self) -> MjStringVec: + ... + @textures.setter + def textures(self, arg1: typing.Any) -> None: + ... + @property + def texuniform(self) -> int: + ... + @texuniform.setter + def texuniform(self, arg1: typing.SupportsInt) -> None: + ... +class MjsMesh: + classname: MjsDefault + content_type: str + file: str + inertia: mujoco._enums.mjtMeshInertia + info: str + name: str + plugin: MjsPlugin + def make_cone(self, nedge: typing.SupportsInt, radius: typing.SupportsFloat) -> None: + ... + def make_hemisphere(self, resolution: typing.SupportsInt) -> None: + ... + def make_plate(self, resolution: typing.Annotated[collections.abc.Sequence[typing.SupportsInt], "FixedSize(2)"] = [0, 0]) -> None: + ... + def make_sphere(self, subdivision: typing.SupportsInt) -> None: + ... + def make_supersphere(self, resolution: typing.SupportsInt, e: typing.SupportsFloat, n: typing.SupportsFloat) -> None: + ... + def make_supertorus(self, resolution: typing.SupportsInt, radius: typing.SupportsFloat, s: typing.SupportsFloat, t: typing.SupportsFloat) -> None: + ... + def make_wedge(self, resolution: typing.Annotated[collections.abc.Sequence[typing.SupportsInt], "FixedSize(2)"] = [0, 0], fov: typing.Annotated[collections.abc.Sequence[typing.SupportsFloat], "FixedSize(2)"] = [0.0, 0.0], gamma: typing.SupportsFloat = 0) -> None: + ... + @property + def id(self) -> int: + ... + @property + def maxhullvert(self) -> int: + ... + @maxhullvert.setter + def maxhullvert(self, arg1: typing.SupportsInt) -> None: + ... + @property + def needsdf(self) -> int: + ... + @needsdf.setter + def needsdf(self, arg1: typing.SupportsInt) -> None: + ... + @property + def refpos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @refpos.setter + def refpos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def refquat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @refquat.setter + def refquat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def scale(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @scale.setter + def scale(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def smoothnormal(self) -> int: + ... + @smoothnormal.setter + def smoothnormal(self, arg1: typing.SupportsInt) -> None: + ... + @property + def userface(self) -> MjIntVec: + ... + @userface.setter + def userface(self, arg1: typing.Any) -> None: + ... + @property + def userfacetexcoord(self) -> MjIntVec: + ... + @userfacetexcoord.setter + def userfacetexcoord(self, arg1: typing.Any) -> None: + ... + @property + def usernormal(self) -> MjFloatVec: + ... + @usernormal.setter + def usernormal(self, arg1: typing.Any) -> None: + ... + @property + def usertexcoord(self) -> MjFloatVec: + ... + @usertexcoord.setter + def usertexcoord(self, arg1: typing.Any) -> None: + ... + @property + def uservert(self) -> MjFloatVec: + ... + @uservert.setter + def uservert(self, arg1: typing.Any) -> None: + ... +class MjsNumeric: + info: str + name: str + @property + def data(self) -> MjDoubleVec: + ... + @data.setter + def data(self, arg1: typing.Any) -> None: + ... + @property + def id(self) -> int: + ... + @property + def signature(self) -> int: + ... + @property + def size(self) -> int: + ... + @size.setter + def size(self, arg1: typing.SupportsInt) -> None: + ... +class MjsOrientation: + type: mujoco._enums.mjtOrientation + @property + def axisangle(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @axisangle.setter + def axisangle(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def euler(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @euler.setter + def euler(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def xyaxes(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable"]: + ... + @xyaxes.setter + def xyaxes(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]"]) -> None: + ... + @property + def zaxis(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @zaxis.setter + def zaxis(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... +class MjsPair: + classname: MjsDefault + geomname1: str + geomname2: str + info: str + name: str + @property + def condim(self) -> int: + ... + @condim.setter + def condim(self, arg1: typing.SupportsInt) -> None: + ... + @property + def friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @friction.setter + def friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def gap(self) -> float: + ... + @gap.setter + def gap(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def id(self) -> int: + ... + @property + def margin(self) -> float: + ... + @margin.setter + def margin(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def solimp(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp.setter + def solimp(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solref(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref.setter + def solref(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def solreffriction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solreffriction.setter + def solreffriction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... +class MjsPlugin: + config: dict + info: str + name: str + plugin_name: str + @property + def active(self) -> int: + ... + @active.setter + def active(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @id.setter + def id(self, arg1: MjsPlugin) -> None: + ... + @property + def signature(self) -> int: + ... +class MjsSensor: + datatype: mujoco._enums.mjtDataType + info: str + name: str + needstage: mujoco._enums.mjtStage + objname: str + objtype: mujoco._enums.mjtObj + plugin: MjsPlugin + refname: str + reftype: mujoco._enums.mjtObj + type: mujoco._enums.mjtSensor + def get_data_size(self) -> int: + ... + @property + def cutoff(self) -> float: + ... + @cutoff.setter + def cutoff(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def dim(self) -> int: + ... + @dim.setter + def dim(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def intprm(self) -> typing.Annotated[numpy.typing.NDArray[numpy.int32], "[3, 1]", "flags.writeable"]: + ... + @intprm.setter + def intprm(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[3, 1]"]) -> None: + ... + @property + def noise(self) -> float: + ... + @noise.setter + def noise(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsSite: + alt: MjsOrientation + classname: MjsDefault + info: str + material: str + name: str + type: mujoco._enums.mjtGeom + def attach_body(self, body: MjsBody, prefix: str | None = None, suffix: str | None = None) -> MjsBody: + ... + def set_frame(self, arg0: MjsFrame) -> None: + ... + @property + def frame(self) -> MjsFrame: + ... + @property + def fromto(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]", "flags.writeable"]: + ... + @fromto.setter + def fromto(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[6, 1]"]) -> None: + ... + @property + def group(self) -> int: + ... + @group.setter + def group(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def parent(self) -> MjsBody: + ... + @property + def pos(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @pos.setter + def pos(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def quat(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]", "flags.writeable"]: + ... + @quat.setter + def quat(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[4, 1]"]) -> None: + ... + @property + def rgba(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @rgba.setter + def rgba(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def size(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @size.setter + def size(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... +class MjsSkin: + file: str + info: str + material: str + name: str + @property + def bindpos(self) -> MjFloatVec: + ... + @bindpos.setter + def bindpos(self, arg1: typing.Any) -> None: + ... + @property + def bindquat(self) -> MjFloatVec: + ... + @bindquat.setter + def bindquat(self, arg1: typing.Any) -> None: + ... + @property + def bodyname(self) -> MjStringVec: + ... + @bodyname.setter + def bodyname(self, arg1: typing.Any) -> None: + ... + @property + def face(self) -> MjIntVec: + ... + @face.setter + def face(self, arg1: typing.Any) -> None: + ... + @property + def group(self) -> int: + ... + @group.setter + def group(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def inflate(self) -> float: + ... + @inflate.setter + def inflate(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def rgba(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @rgba.setter + def rgba(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def texcoord(self) -> MjFloatVec: + ... + @texcoord.setter + def texcoord(self, arg1: typing.Any) -> None: + ... + @property + def vert(self) -> MjFloatVec: + ... + @vert.setter + def vert(self, arg1: typing.Any) -> None: + ... + @property + def vertid(self) -> list: + ... + @vertid.setter + def vertid(self, arg1: typing.Any) -> None: + ... + @property + def vertweight(self) -> list: + ... + @vertweight.setter + def vertweight(self, arg1: typing.Any) -> None: + ... +class MjsTendon: + info: str + material: str + name: str + def default(self) -> MjsDefault: + ... + def wrap_geom(self, arg0: str, arg1: str) -> MjsWrap: + ... + def wrap_joint(self, arg0: str, arg1: typing.SupportsFloat) -> MjsWrap: + ... + def wrap_pulley(self, arg0: typing.SupportsFloat) -> MjsWrap: + ... + def wrap_site(self, arg0: str) -> MjsWrap: + ... + @property + def actfrclimited(self) -> int: + ... + @actfrclimited.setter + def actfrclimited(self, arg1: typing.SupportsInt) -> None: + ... + @property + def actfrcrange(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @actfrcrange.setter + def actfrcrange(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def armature(self) -> float: + ... + @armature.setter + def armature(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def damping(self) -> float: + ... + @damping.setter + def damping(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def frictionloss(self) -> float: + ... + @frictionloss.setter + def frictionloss(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def group(self) -> int: + ... + @group.setter + def group(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def limited(self) -> int: + ... + @limited.setter + def limited(self, arg1: typing.SupportsInt) -> None: + ... + @property + def margin(self) -> float: + ... + @margin.setter + def margin(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def range(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @range.setter + def range(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def rgba(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]", "flags.writeable"]: + ... + @rgba.setter + def rgba(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float32], "[4, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def solimp_friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp_friction.setter + def solimp_friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solimp_limit(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]", "flags.writeable"]: + ... + @solimp_limit.setter + def solimp_limit(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[5, 1]"]) -> None: + ... + @property + def solref_friction(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref_friction.setter + def solref_friction(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def solref_limit(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @solref_limit.setter + def solref_limit(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def springlength(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]", "flags.writeable"]: + ... + @springlength.setter + def springlength(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[2, 1]"]) -> None: + ... + @property + def stiffness(self) -> float: + ... + @stiffness.setter + def stiffness(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def userdata(self) -> MjDoubleVec: + ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: + ... + @property + def width(self) -> float: + ... + @width.setter + def width(self, arg1: typing.SupportsFloat) -> None: + ... +class MjsText: + data: str + info: str + name: str + @property + def id(self) -> int: + ... + @property + def signature(self) -> int: + ... +class MjsTexture: + colorspace: mujoco._enums.mjtColorSpace + content_type: str + file: str + info: str + name: str + type: mujoco._enums.mjtTexture + @property + def builtin(self) -> int: + ... + @builtin.setter + def builtin(self, arg1: typing.SupportsInt) -> None: + ... + @property + def cubefiles(self) -> MjStringVec: + ... + @cubefiles.setter + def cubefiles(self, arg1: typing.Any) -> None: + ... + @property + def data(self) -> MjByteVec: + ... + @data.setter + def data(self, arg1: bytes) -> None: + ... + @property + def gridlayout(self) -> MjCharVec: + ... + @gridlayout.setter + def gridlayout(self, arg1: typing.Any) -> None: + ... + @property + def gridsize(self) -> typing.Annotated[numpy.typing.NDArray[numpy.int32], "[2, 1]", "flags.writeable"]: + ... + @gridsize.setter + def gridsize(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.int32], "[2, 1]"]) -> None: + ... + @property + def height(self) -> int: + ... + @height.setter + def height(self, arg1: typing.SupportsInt) -> None: + ... + @property + def hflip(self) -> int: + ... + @hflip.setter + def hflip(self, arg1: typing.SupportsInt) -> None: + ... + @property + def id(self) -> int: + ... + @property + def mark(self) -> int: + ... + @mark.setter + def mark(self, arg1: typing.SupportsInt) -> None: + ... + @property + def markrgb(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @markrgb.setter + def markrgb(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def nchannel(self) -> int: + ... + @nchannel.setter + def nchannel(self, arg1: typing.SupportsInt) -> None: + ... + @property + def random(self) -> float: + ... + @random.setter + def random(self, arg1: typing.SupportsFloat) -> None: + ... + @property + def rgb1(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @rgb1.setter + def rgb1(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def rgb2(self) -> typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]", "flags.writeable"]: + ... + @rgb2.setter + def rgb2(self, arg1: typing.Annotated[numpy.typing.NDArray[numpy.float64], "[3, 1]"]) -> None: + ... + @property + def signature(self) -> int: + ... + @property + def vflip(self) -> int: + ... + @vflip.setter + def vflip(self, arg1: typing.SupportsInt) -> None: + ... + @property + def width(self) -> int: + ... + @width.setter + def width(self, arg1: typing.SupportsInt) -> None: + ... +class MjsTuple: + info: str + name: str + @property + def id(self) -> int: + ... + @property + def objname(self) -> MjStringVec: + ... + @objname.setter + def objname(self, arg1: typing.Any) -> None: + ... + @property + def objprm(self) -> MjDoubleVec: + ... + @objprm.setter + def objprm(self, arg1: typing.Any) -> None: + ... + @property + def objtype(self) -> MjIntVec: + ... + @objtype.setter + def objtype(self, arg1: typing.Any) -> None: + ... + @property + def signature(self) -> int: + ... +class MjsWrap: + info: str diff --git a/typings/mujoco/_structs.pyi b/typings/mujoco/_structs.pyi new file mode 100644 index 000000000..090c90667 --- /dev/null +++ b/typings/mujoco/_structs.pyi @@ -0,0 +1,5829 @@ +from __future__ import annotations +import mujoco._enums +import numpy +import numpy.typing +import typing + +__all__: list[str] = [ + "MjContact", + "MjData", + "MjLROpt", + "MjModel", + "MjOption", + "MjSolverStat", + "MjStatistic", + "MjTimerStat", + "MjVisual", + "MjWarningStat", + "MjvCamera", + "MjvFigure", + "MjvGLCamera", + "MjvGeom", + "MjvLight", + "MjvOption", + "MjvPerturb", + "MjvScene", + "mjv_averageCamera", +] + +class MjContact: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjContact: ... + def __deepcopy__(self, arg0: dict) -> MjContact: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def H(self) -> numpy.typing.NDArray[numpy.float64]: ... + @H.setter + def H(self, arg1: typing.Any) -> None: ... + @property + def dim(self) -> int: ... + @dim.setter + def dim(self, arg1: typing.SupportsInt) -> None: ... + @property + def dist(self) -> float: ... + @dist.setter + def dist(self, arg1: typing.SupportsFloat) -> None: ... + @property + def efc_address(self) -> int: ... + @efc_address.setter + def efc_address(self, arg1: typing.SupportsInt) -> None: ... + @property + def elem(self) -> numpy.typing.NDArray[numpy.int32]: ... + @elem.setter + def elem(self, arg1: typing.Any) -> None: ... + @property + def exclude(self) -> int: ... + @exclude.setter + def exclude(self, arg1: typing.SupportsInt) -> None: ... + @property + def flex(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex.setter + def flex(self, arg1: typing.Any) -> None: ... + @property + def frame(self) -> numpy.typing.NDArray[numpy.float64]: ... + @frame.setter + def frame(self, arg1: typing.Any) -> None: ... + @property + def friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @friction.setter + def friction(self, arg1: typing.Any) -> None: ... + @property + def geom(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom.setter + def geom(self, arg1: typing.Any) -> None: ... + @property + def geom1(self) -> int: ... + @geom1.setter + def geom1(self, arg1: typing.SupportsInt) -> None: ... + @property + def geom2(self) -> int: ... + @geom2.setter + def geom2(self, arg1: typing.SupportsInt) -> None: ... + @property + def includemargin(self) -> float: ... + @includemargin.setter + def includemargin(self, arg1: typing.SupportsFloat) -> None: ... + @property + def mu(self) -> float: ... + @mu.setter + def mu(self, arg1: typing.SupportsFloat) -> None: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solimp.setter + def solimp(self, arg1: typing.Any) -> None: ... + @property + def solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solref.setter + def solref(self, arg1: typing.Any) -> None: ... + @property + def solreffriction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solreffriction.setter + def solreffriction(self, arg1: typing.Any) -> None: ... + @property + def vert(self) -> numpy.typing.NDArray[numpy.int32]: ... + @vert.setter + def vert(self, arg1: typing.Any) -> None: ... + +class MjData: + @staticmethod + def bind( + data: MjData, + specs: typing.Union[ + typing.Sequence[ + typing.Union[ + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ] + ], + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ], + ): + """ + Bind a Mujoco spec to a mjData. + + Args: + data: The mjData to bind to. + specs: The mjSpec elements to use for binding, can be a single element or a + sequence. + Returns: + A MjDataGroupedViews object or a list of the same type. + """ + def __copy__(self) -> MjData: ... + def __deepcopy__(self, arg0: dict) -> MjData: ... + def __getstate__(self) -> bytes: ... + def __init__(self, arg0: MjModel) -> None: ... + def __setstate__(self, arg0: bytes) -> None: ... + @typing.overload + def actuator(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def actuator(self, name: str = "") -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsActuator_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsBody_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsCamera_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsGeom_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsJoint_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsLight_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsSensor_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsSite_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsTendon_ = None) -> ...: ... + @typing.overload + def body(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def body(self, name: str = "") -> ...: ... + @typing.overload + def cam(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def cam(self, name: str = "") -> ...: ... + @typing.overload + def camera(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def camera(self, name: str = "") -> ...: ... + @typing.overload + def geom(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def geom(self, name: str = "") -> ...: ... + @typing.overload + def jnt(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def jnt(self, name: str = "") -> ...: ... + @typing.overload + def joint(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def joint(self, name: str = "") -> ...: ... + @typing.overload + def light(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def light(self, name: str = "") -> ...: ... + @typing.overload + def sensor(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def sensor(self, name: str = "") -> ...: ... + @typing.overload + def site(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def site(self, name: str = "") -> ...: ... + @typing.overload + def ten(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def ten(self, name: str = "") -> ...: ... + @typing.overload + def tendon(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def tendon(self, name: str = "") -> ...: ... + @property + def M(self) -> numpy.typing.NDArray[numpy.float64]: ... + @M.setter + def M(self, arg1: typing.Any) -> None: ... + @property + def _address(self) -> int: ... + @property + def act(self) -> numpy.typing.NDArray[numpy.float64]: ... + @act.setter + def act(self, arg1: typing.Any) -> None: ... + @property + def act_dot(self) -> numpy.typing.NDArray[numpy.float64]: ... + @act_dot.setter + def act_dot(self, arg1: typing.Any) -> None: ... + @property + def actuator_force(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_force.setter + def actuator_force(self, arg1: typing.Any) -> None: ... + @property + def actuator_length(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_length.setter + def actuator_length(self, arg1: typing.Any) -> None: ... + @property + def actuator_moment(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_moment.setter + def actuator_moment(self, arg1: typing.Any) -> None: ... + @property + def actuator_velocity(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_velocity.setter + def actuator_velocity(self, arg1: typing.Any) -> None: ... + @property + def bvh_aabb_dyn(self) -> numpy.typing.NDArray[numpy.float64]: ... + @bvh_aabb_dyn.setter + def bvh_aabb_dyn(self, arg1: typing.Any) -> None: ... + @property + def bvh_active(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @bvh_active.setter + def bvh_active(self, arg1: typing.Any) -> None: ... + @property + def cacc(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cacc.setter + def cacc(self, arg1: typing.Any) -> None: ... + @property + def cam_xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_xmat.setter + def cam_xmat(self, arg1: typing.Any) -> None: ... + @property + def cam_xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_xpos.setter + def cam_xpos(self, arg1: typing.Any) -> None: ... + @property + def cdof(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cdof.setter + def cdof(self, arg1: typing.Any) -> None: ... + @property + def cdof_dot(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cdof_dot.setter + def cdof_dot(self, arg1: typing.Any) -> None: ... + @property + def cfrc_ext(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cfrc_ext.setter + def cfrc_ext(self, arg1: typing.Any) -> None: ... + @property + def cfrc_int(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cfrc_int.setter + def cfrc_int(self, arg1: typing.Any) -> None: ... + @property + def cinert(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cinert.setter + def cinert(self, arg1: typing.Any) -> None: ... + @property + def contact(self) -> _MjContactList: ... + @property + def crb(self) -> numpy.typing.NDArray[numpy.float64]: ... + @crb.setter + def crb(self, arg1: typing.Any) -> None: ... + @property + def ctrl(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ctrl.setter + def ctrl(self, arg1: typing.Any) -> None: ... + @property + def cvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cvel.setter + def cvel(self, arg1: typing.Any) -> None: ... + @property + def dof_island(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_AR(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_AR_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_AR_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_AR_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_D(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_J(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_JT(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_JT_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_JT_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_JT_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_JT_rowsuper(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_J_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_J_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_J_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_J_rowsuper(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_KBIP(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_R(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_aref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_b(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_diagApprox(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_force(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_frictionloss(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_id(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_island(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_state(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def efc_vel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def energy(self) -> numpy.typing.NDArray[numpy.float64]: ... + @energy.setter + def energy(self, arg1: typing.Any) -> None: ... + @property + def eq_active(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @eq_active.setter + def eq_active(self, arg1: typing.Any) -> None: ... + @property + def flexedge_J(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flexedge_J.setter + def flexedge_J(self, arg1: typing.Any) -> None: ... + @property + def flexedge_J_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexedge_J_colind.setter + def flexedge_J_colind(self, arg1: typing.Any) -> None: ... + @property + def flexedge_J_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexedge_J_rowadr.setter + def flexedge_J_rowadr(self, arg1: typing.Any) -> None: ... + @property + def flexedge_J_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexedge_J_rownnz.setter + def flexedge_J_rownnz(self, arg1: typing.Any) -> None: ... + @property + def flexedge_length(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flexedge_length.setter + def flexedge_length(self, arg1: typing.Any) -> None: ... + @property + def flexedge_velocity(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flexedge_velocity.setter + def flexedge_velocity(self, arg1: typing.Any) -> None: ... + @property + def flexelem_aabb(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flexelem_aabb.setter + def flexelem_aabb(self, arg1: typing.Any) -> None: ... + @property + def flexvert_xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flexvert_xpos.setter + def flexvert_xpos(self, arg1: typing.Any) -> None: ... + @property + def geom_xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_xmat.setter + def geom_xmat(self, arg1: typing.Any) -> None: ... + @property + def geom_xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_xpos.setter + def geom_xpos(self, arg1: typing.Any) -> None: ... + @property + def iLD(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iLDiagInv(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iM(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iM_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iM_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iM_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iacc(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iacc_smooth(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_D(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_J(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_JT(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_JT_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_JT_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_JT_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_JT_rowsuper(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_J_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_J_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_J_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_J_rowsuper(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_R(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_aref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_force(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_frictionloss(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def iefc_id(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_state(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def iefc_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def ifrc_constraint(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def ifrc_smooth(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def island_dofadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def island_idofadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def island_iefcadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def island_ne(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def island_nefc(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def island_nf(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def island_nv(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def light_xdir(self) -> numpy.typing.NDArray[numpy.float64]: ... + @light_xdir.setter + def light_xdir(self, arg1: typing.Any) -> None: ... + @property + def light_xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @light_xpos.setter + def light_xpos(self, arg1: typing.Any) -> None: ... + @property + def map_dof2idof(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def map_efc2iefc(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def map_idof2dof(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def map_iefc2efc(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def maxuse_arena(self) -> int: ... + @maxuse_arena.setter + def maxuse_arena(self, arg1: typing.SupportsInt) -> None: ... + @property + def maxuse_con(self) -> int: ... + @maxuse_con.setter + def maxuse_con(self, arg1: typing.SupportsInt) -> None: ... + @property + def maxuse_efc(self) -> int: ... + @maxuse_efc.setter + def maxuse_efc(self, arg1: typing.SupportsInt) -> None: ... + @property + def maxuse_stack(self) -> int: ... + @maxuse_stack.setter + def maxuse_stack(self, arg1: typing.SupportsInt) -> None: ... + @property + def maxuse_threadstack(self) -> numpy.typing.NDArray[numpy.uint64]: ... + @maxuse_threadstack.setter + def maxuse_threadstack(self, arg1: typing.Any) -> None: ... + @property + def mocap_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mocap_pos.setter + def mocap_pos(self, arg1: typing.Any) -> None: ... + @property + def mocap_quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mocap_quat.setter + def mocap_quat(self, arg1: typing.Any) -> None: ... + @property + def model(self) -> MjModel: ... + @property + def moment_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @moment_colind.setter + def moment_colind(self, arg1: typing.Any) -> None: ... + @property + def moment_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @moment_rowadr.setter + def moment_rowadr(self, arg1: typing.Any) -> None: ... + @property + def moment_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @moment_rownnz.setter + def moment_rownnz(self, arg1: typing.Any) -> None: ... + @property + def nA(self) -> int: ... + @nA.setter + def nA(self, arg1: typing.SupportsInt) -> None: ... + @property + def nJ(self) -> int: ... + @nJ.setter + def nJ(self, arg1: typing.SupportsInt) -> None: ... + @property + def narena(self) -> int: ... + @narena.setter + def narena(self, arg1: typing.SupportsInt) -> None: ... + @property + def nbuffer(self) -> int: ... + @nbuffer.setter + def nbuffer(self, arg1: typing.SupportsInt) -> None: ... + @property + def ncon(self) -> int: ... + @ncon.setter + def ncon(self, arg1: typing.SupportsInt) -> None: ... + @property + def ne(self) -> int: ... + @ne.setter + def ne(self, arg1: typing.SupportsInt) -> None: ... + @property + def nefc(self) -> int: ... + @nefc.setter + def nefc(self, arg1: typing.SupportsInt) -> None: ... + @property + def nf(self) -> int: ... + @nf.setter + def nf(self, arg1: typing.SupportsInt) -> None: ... + @property + def nidof(self) -> int: ... + @nidof.setter + def nidof(self, arg1: typing.SupportsInt) -> None: ... + @property + def nisland(self) -> int: ... + @nisland.setter + def nisland(self, arg1: typing.SupportsInt) -> None: ... + @property + def nl(self) -> int: ... + @nl.setter + def nl(self, arg1: typing.SupportsInt) -> None: ... + @property + def nplugin(self) -> int: ... + @nplugin.setter + def nplugin(self, arg1: typing.SupportsInt) -> None: ... + @property + def parena(self) -> int: ... + @parena.setter + def parena(self, arg1: typing.SupportsInt) -> None: ... + @property + def pbase(self) -> int: ... + @pbase.setter + def pbase(self, arg1: typing.SupportsInt) -> None: ... + @property + def plugin(self) -> numpy.typing.NDArray[numpy.int32]: ... + @plugin.setter + def plugin(self, arg1: typing.Any) -> None: ... + @property + def plugin_data(self) -> numpy.typing.NDArray[numpy.uint64]: ... + @plugin_data.setter + def plugin_data(self, arg1: typing.Any) -> None: ... + @property + def plugin_state(self) -> numpy.typing.NDArray[numpy.float64]: ... + @plugin_state.setter + def plugin_state(self, arg1: typing.Any) -> None: ... + @property + def pstack(self) -> int: ... + @pstack.setter + def pstack(self, arg1: typing.SupportsInt) -> None: ... + @property + def qDeriv(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qDeriv.setter + def qDeriv(self, arg1: typing.Any) -> None: ... + @property + def qH(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qH.setter + def qH(self, arg1: typing.Any) -> None: ... + @property + def qHDiagInv(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qHDiagInv.setter + def qHDiagInv(self, arg1: typing.Any) -> None: ... + @property + def qLD(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qLD.setter + def qLD(self, arg1: typing.Any) -> None: ... + @property + def qLDiagInv(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qLDiagInv.setter + def qLDiagInv(self, arg1: typing.Any) -> None: ... + @property + def qLU(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qLU.setter + def qLU(self, arg1: typing.Any) -> None: ... + @property + def qM(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qM.setter + def qM(self, arg1: typing.Any) -> None: ... + @property + def qacc(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qacc.setter + def qacc(self, arg1: typing.Any) -> None: ... + @property + def qacc_smooth(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qacc_smooth.setter + def qacc_smooth(self, arg1: typing.Any) -> None: ... + @property + def qacc_warmstart(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qacc_warmstart.setter + def qacc_warmstart(self, arg1: typing.Any) -> None: ... + @property + def qfrc_actuator(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_actuator.setter + def qfrc_actuator(self, arg1: typing.Any) -> None: ... + @property + def qfrc_applied(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_applied.setter + def qfrc_applied(self, arg1: typing.Any) -> None: ... + @property + def qfrc_bias(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_bias.setter + def qfrc_bias(self, arg1: typing.Any) -> None: ... + @property + def qfrc_constraint(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_constraint.setter + def qfrc_constraint(self, arg1: typing.Any) -> None: ... + @property + def qfrc_damper(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_damper.setter + def qfrc_damper(self, arg1: typing.Any) -> None: ... + @property + def qfrc_fluid(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_fluid.setter + def qfrc_fluid(self, arg1: typing.Any) -> None: ... + @property + def qfrc_gravcomp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_gravcomp.setter + def qfrc_gravcomp(self, arg1: typing.Any) -> None: ... + @property + def qfrc_inverse(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_inverse.setter + def qfrc_inverse(self, arg1: typing.Any) -> None: ... + @property + def qfrc_passive(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_passive.setter + def qfrc_passive(self, arg1: typing.Any) -> None: ... + @property + def qfrc_smooth(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_smooth.setter + def qfrc_smooth(self, arg1: typing.Any) -> None: ... + @property + def qfrc_spring(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_spring.setter + def qfrc_spring(self, arg1: typing.Any) -> None: ... + @property + def qpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qpos.setter + def qpos(self, arg1: typing.Any) -> None: ... + @property + def qvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qvel.setter + def qvel(self, arg1: typing.Any) -> None: ... + @property + def sensordata(self) -> numpy.typing.NDArray[numpy.float64]: ... + @sensordata.setter + def sensordata(self, arg1: typing.Any) -> None: ... + @property + def signature(self) -> int: ... + @property + def site_xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @site_xmat.setter + def site_xmat(self, arg1: typing.Any) -> None: ... + @property + def site_xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @site_xpos.setter + def site_xpos(self, arg1: typing.Any) -> None: ... + @property + def solver(self) -> _MjSolverStatList: ... + @property + def solver_fwdinv(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solver_fwdinv.setter + def solver_fwdinv(self, arg1: typing.Any) -> None: ... + @property + def solver_niter(self) -> numpy.typing.NDArray[numpy.int32]: ... + @solver_niter.setter + def solver_niter(self, arg1: typing.Any) -> None: ... + @property + def solver_nnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @solver_nnz.setter + def solver_nnz(self, arg1: typing.Any) -> None: ... + @property + def subtree_angmom(self) -> numpy.typing.NDArray[numpy.float64]: ... + @subtree_angmom.setter + def subtree_angmom(self, arg1: typing.Any) -> None: ... + @property + def subtree_com(self) -> numpy.typing.NDArray[numpy.float64]: ... + @subtree_com.setter + def subtree_com(self, arg1: typing.Any) -> None: ... + @property + def subtree_linvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @subtree_linvel.setter + def subtree_linvel(self, arg1: typing.Any) -> None: ... + @property + def ten_J(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ten_J.setter + def ten_J(self, arg1: typing.Any) -> None: ... + @property + def ten_J_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @ten_J_colind.setter + def ten_J_colind(self, arg1: typing.Any) -> None: ... + @property + def ten_J_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @ten_J_rowadr.setter + def ten_J_rowadr(self, arg1: typing.Any) -> None: ... + @property + def ten_J_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @ten_J_rownnz.setter + def ten_J_rownnz(self, arg1: typing.Any) -> None: ... + @property + def ten_length(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ten_length.setter + def ten_length(self, arg1: typing.Any) -> None: ... + @property + def ten_velocity(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ten_velocity.setter + def ten_velocity(self, arg1: typing.Any) -> None: ... + @property + def ten_wrapadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @ten_wrapadr.setter + def ten_wrapadr(self, arg1: typing.Any) -> None: ... + @property + def ten_wrapnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @ten_wrapnum.setter + def ten_wrapnum(self, arg1: typing.Any) -> None: ... + @property + def tendon_efcadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def threadpool(self) -> int: ... + @threadpool.setter + def threadpool(self, arg1: typing.SupportsInt) -> None: ... + @property + def time(self) -> float: ... + @time.setter + def time(self, arg1: typing.SupportsFloat) -> None: ... + @property + def timer(self) -> _MjTimerStatList: ... + @property + def userdata(self) -> numpy.typing.NDArray[numpy.float64]: ... + @userdata.setter + def userdata(self, arg1: typing.Any) -> None: ... + @property + def warning(self) -> _MjWarningStatList: ... + @property + def wrap_obj(self) -> numpy.typing.NDArray[numpy.int32]: ... + @wrap_obj.setter + def wrap_obj(self, arg1: typing.Any) -> None: ... + @property + def wrap_xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @wrap_xpos.setter + def wrap_xpos(self, arg1: typing.Any) -> None: ... + @property + def xanchor(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xanchor.setter + def xanchor(self, arg1: typing.Any) -> None: ... + @property + def xaxis(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xaxis.setter + def xaxis(self, arg1: typing.Any) -> None: ... + @property + def xfrc_applied(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xfrc_applied.setter + def xfrc_applied(self, arg1: typing.Any) -> None: ... + @property + def ximat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ximat.setter + def ximat(self, arg1: typing.Any) -> None: ... + @property + def xipos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xipos.setter + def xipos(self, arg1: typing.Any) -> None: ... + @property + def xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xmat.setter + def xmat(self, arg1: typing.Any) -> None: ... + @property + def xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xpos.setter + def xpos(self, arg1: typing.Any) -> None: ... + @property + def xquat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xquat.setter + def xquat(self, arg1: typing.Any) -> None: ... + +class MjLROpt: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjLROpt: ... + def __deepcopy__(self, arg0: dict) -> MjLROpt: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def accel(self) -> float: ... + @accel.setter + def accel(self, arg0: typing.SupportsFloat) -> None: ... + @property + def interval(self) -> float: ... + @interval.setter + def interval(self, arg0: typing.SupportsFloat) -> None: ... + @property + def inttotal(self) -> float: ... + @inttotal.setter + def inttotal(self, arg0: typing.SupportsFloat) -> None: ... + @property + def maxforce(self) -> float: ... + @maxforce.setter + def maxforce(self, arg0: typing.SupportsFloat) -> None: ... + @property + def mode(self) -> int: ... + @mode.setter + def mode(self, arg0: typing.SupportsInt) -> None: ... + @property + def timeconst(self) -> float: ... + @timeconst.setter + def timeconst(self, arg0: typing.SupportsFloat) -> None: ... + @property + def timestep(self) -> float: ... + @timestep.setter + def timestep(self, arg0: typing.SupportsFloat) -> None: ... + @property + def tolrange(self) -> float: ... + @tolrange.setter + def tolrange(self, arg0: typing.SupportsFloat) -> None: ... + @property + def useexisting(self) -> int: ... + @useexisting.setter + def useexisting(self, arg0: typing.SupportsInt) -> None: ... + @property + def uselimit(self) -> int: ... + @uselimit.setter + def uselimit(self, arg0: typing.SupportsInt) -> None: ... + +class MjModel: + _size_fields: typing.ClassVar[tuple] = ( + "nq", + "nv", + "nu", + "na", + "nbody", + "nbvh", + "nbvhstatic", + "nbvhdynamic", + "noct", + "njnt", + "ntree", + "nM", + "nB", + "nC", + "nD", + "ngeom", + "nsite", + "ncam", + "nlight", + "nflex", + "nflexnode", + "nflexvert", + "nflexedge", + "nflexelem", + "nflexelemdata", + "nflexelemedge", + "nflexshelldata", + "nflexevpair", + "nflextexcoord", + "nmesh", + "nmeshvert", + "nmeshnormal", + "nmeshtexcoord", + "nmeshface", + "nmeshgraph", + "nmeshpoly", + "nmeshpolyvert", + "nmeshpolymap", + "nskin", + "nskinvert", + "nskintexvert", + "nskinface", + "nskinbone", + "nskinbonevert", + "nhfield", + "nhfielddata", + "ntex", + "ntexdata", + "nmat", + "npair", + "nexclude", + "neq", + "ntendon", + "nwrap", + "nsensor", + "nnumeric", + "nnumericdata", + "ntext", + "ntextdata", + "ntuple", + "ntupledata", + "nkey", + "nmocap", + "nplugin", + "npluginattr", + "nuser_body", + "nuser_jnt", + "nuser_geom", + "nuser_site", + "nuser_cam", + "nuser_tendon", + "nuser_actuator", + "nuser_sensor", + "nnames", + "npaths", + "nnames_map", + "nJmom", + "ngravcomp", + "nemax", + "njmax", + "nconmax", + "nuserdata", + "nsensordata", + "npluginstate", + "narena", + "nbuffer", + ) + @staticmethod + def _from_model_ptr(arg0: typing.SupportsInt) -> MjModel: ... + @staticmethod + def bind( + model: MjModel, + specs: typing.Union[ + typing.Sequence[ + typing.Union[ + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ] + ], + mujoco._specs.MjsBody, + mujoco._specs.MjsFrame, + mujoco._specs.MjsGeom, + mujoco._specs.MjsJoint, + mujoco._specs.MjsLight, + mujoco._specs.MjsMaterial, + mujoco._specs.MjsSite, + mujoco._specs.MjsMesh, + mujoco._specs.MjsSkin, + mujoco._specs.MjsTexture, + mujoco._specs.MjsText, + mujoco._specs.MjsTuple, + mujoco._specs.MjsCamera, + mujoco._specs.MjsFlex, + mujoco._specs.MjsHField, + mujoco._specs.MjsKey, + mujoco._specs.MjsNumeric, + mujoco._specs.MjsPair, + mujoco._specs.MjsExclude, + mujoco._specs.MjsEquality, + mujoco._specs.MjsTendon, + mujoco._specs.MjsSensor, + mujoco._specs.MjsActuator, + mujoco._specs.MjsPlugin, + ], + ): + """ + Bind a Mujoco spec to a mjModel. + + Args: + model: The mjModel to bind to. + specs: The mjSpec elements to use for binding, can be a single element or a + sequence. + Returns: + A MjModelGroupedViews object or a list of the same type. + """ + @staticmethod + def from_binary_path( + filename: str, assets: collections.abc.Mapping[str, bytes] | None = None + ) -> MjModel: + """ + Loads an MjModel from an MJB file and an optional assets dictionary. + + The filename for the MJB can also refer to a key in the assets dictionary. + This is useful for example when the MJB is not available as a file on disk. + """ + @staticmethod + def from_xml_path( + filename: str, assets: collections.abc.Mapping[str, bytes] | None = None + ) -> MjModel: + """ + Loads an MjModel from an XML file and an optional assets dictionary. + + The filename for the XML can also refer to a key in the assets dictionary. + This is useful for example when the XML is not available as a file on disk. + """ + @staticmethod + def from_xml_string( + xml: str, assets: collections.abc.Mapping[str, bytes] | None = None + ) -> MjModel: + """ + Loads an MjModel from an XML string and an optional assets dictionary. + """ + def __copy__(self) -> MjModel: ... + def __deepcopy__(self, arg0: dict) -> MjModel: ... + def __getstate__(self) -> bytes: ... + def __setstate__(self, arg0: bytes) -> None: ... + @typing.overload + def actuator(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def actuator(self, name: str = "") -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsActuator_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsBody_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsCamera_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsEquality_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsExclude_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsGeom_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsHField_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsJoint_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsLight_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsMaterial_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsMesh_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsNumeric_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsPair_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsSensor_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsSite_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsSkin_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsTendon_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsTexture_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsTuple_ = None) -> ...: ... + @typing.overload + def bind_scalar(self, spec: mjsKey_ = None) -> ...: ... + @typing.overload + def body(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def body(self, name: str = "") -> ...: ... + @typing.overload + def cam(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def cam(self, name: str = "") -> ...: ... + @typing.overload + def camera(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def camera(self, name: str = "") -> ...: ... + @typing.overload + def eq(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def eq(self, name: str = "") -> ...: ... + @typing.overload + def equality(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def equality(self, name: str = "") -> ...: ... + @typing.overload + def exclude(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def exclude(self, name: str = "") -> ...: ... + @typing.overload + def geom(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def geom(self, name: str = "") -> ...: ... + @typing.overload + def hfield(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def hfield(self, name: str = "") -> ...: ... + @typing.overload + def jnt(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def jnt(self, name: str = "") -> ...: ... + @typing.overload + def joint(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def joint(self, name: str = "") -> ...: ... + @typing.overload + def key(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def key(self, name: str = "") -> ...: ... + @typing.overload + def keyframe(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def keyframe(self, name: str = "") -> ...: ... + @typing.overload + def light(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def light(self, name: str = "") -> ...: ... + @typing.overload + def mat(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def mat(self, name: str = "") -> ...: ... + @typing.overload + def material(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def material(self, name: str = "") -> ...: ... + @typing.overload + def mesh(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def mesh(self, name: str = "") -> ...: ... + @typing.overload + def numeric(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def numeric(self, name: str = "") -> ...: ... + @typing.overload + def pair(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def pair(self, name: str = "") -> ...: ... + @typing.overload + def sensor(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def sensor(self, name: str = "") -> ...: ... + @typing.overload + def site(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def site(self, name: str = "") -> ...: ... + @typing.overload + def skin(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def skin(self, name: str = "") -> ...: ... + @typing.overload + def tendon(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def tendon(self, name: str = "") -> ...: ... + @typing.overload + def tex(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def tex(self, name: str = "") -> ...: ... + @typing.overload + def texture(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def texture(self, name: str = "") -> ...: ... + @typing.overload + def tuple(self, arg0: typing.SupportsInt) -> ...: ... + @typing.overload + def tuple(self, name: str = "") -> ...: ... + @property + def B_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @B_colind.setter + def B_colind(self, arg1: typing.Any) -> None: ... + @property + def B_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @B_rowadr.setter + def B_rowadr(self, arg1: typing.Any) -> None: ... + @property + def B_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @B_rownnz.setter + def B_rownnz(self, arg1: typing.Any) -> None: ... + @property + def D_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @D_colind.setter + def D_colind(self, arg1: typing.Any) -> None: ... + @property + def D_diag(self) -> numpy.typing.NDArray[numpy.int32]: ... + @D_diag.setter + def D_diag(self, arg1: typing.Any) -> None: ... + @property + def D_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @D_rowadr.setter + def D_rowadr(self, arg1: typing.Any) -> None: ... + @property + def D_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @D_rownnz.setter + def D_rownnz(self, arg1: typing.Any) -> None: ... + @property + def M_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @M_colind.setter + def M_colind(self, arg1: typing.Any) -> None: ... + @property + def M_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @M_rowadr.setter + def M_rowadr(self, arg1: typing.Any) -> None: ... + @property + def M_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @M_rownnz.setter + def M_rownnz(self, arg1: typing.Any) -> None: ... + @property + def _address(self) -> int: ... + @property + def _sizes(self) -> numpy.typing.NDArray[numpy.int64]: ... + @property + def actuator_acc0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_acc0.setter + def actuator_acc0(self, arg1: typing.Any) -> None: ... + @property + def actuator_actadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_actadr.setter + def actuator_actadr(self, arg1: typing.Any) -> None: ... + @property + def actuator_actearly(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @actuator_actearly.setter + def actuator_actearly(self, arg1: typing.Any) -> None: ... + @property + def actuator_actlimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @actuator_actlimited.setter + def actuator_actlimited(self, arg1: typing.Any) -> None: ... + @property + def actuator_actnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_actnum.setter + def actuator_actnum(self, arg1: typing.Any) -> None: ... + @property + def actuator_actrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_actrange.setter + def actuator_actrange(self, arg1: typing.Any) -> None: ... + @property + def actuator_biasprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_biasprm.setter + def actuator_biasprm(self, arg1: typing.Any) -> None: ... + @property + def actuator_biastype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_biastype.setter + def actuator_biastype(self, arg1: typing.Any) -> None: ... + @property + def actuator_cranklength(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_cranklength.setter + def actuator_cranklength(self, arg1: typing.Any) -> None: ... + @property + def actuator_ctrllimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @actuator_ctrllimited.setter + def actuator_ctrllimited(self, arg1: typing.Any) -> None: ... + @property + def actuator_ctrlrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_ctrlrange.setter + def actuator_ctrlrange(self, arg1: typing.Any) -> None: ... + @property + def actuator_dynprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_dynprm.setter + def actuator_dynprm(self, arg1: typing.Any) -> None: ... + @property + def actuator_dyntype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_dyntype.setter + def actuator_dyntype(self, arg1: typing.Any) -> None: ... + @property + def actuator_forcelimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @actuator_forcelimited.setter + def actuator_forcelimited(self, arg1: typing.Any) -> None: ... + @property + def actuator_forcerange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_forcerange.setter + def actuator_forcerange(self, arg1: typing.Any) -> None: ... + @property + def actuator_gainprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_gainprm.setter + def actuator_gainprm(self, arg1: typing.Any) -> None: ... + @property + def actuator_gaintype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_gaintype.setter + def actuator_gaintype(self, arg1: typing.Any) -> None: ... + @property + def actuator_gear(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_gear.setter + def actuator_gear(self, arg1: typing.Any) -> None: ... + @property + def actuator_group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_group.setter + def actuator_group(self, arg1: typing.Any) -> None: ... + @property + def actuator_length0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_length0.setter + def actuator_length0(self, arg1: typing.Any) -> None: ... + @property + def actuator_lengthrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_lengthrange.setter + def actuator_lengthrange(self, arg1: typing.Any) -> None: ... + @property + def actuator_plugin(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_plugin.setter + def actuator_plugin(self, arg1: typing.Any) -> None: ... + @property + def actuator_trnid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_trnid.setter + def actuator_trnid(self, arg1: typing.Any) -> None: ... + @property + def actuator_trntype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actuator_trntype.setter + def actuator_trntype(self, arg1: typing.Any) -> None: ... + @property + def actuator_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actuator_user.setter + def actuator_user(self, arg1: typing.Any) -> None: ... + @property + def body_bvhadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_bvhadr.setter + def body_bvhadr(self, arg1: typing.Any) -> None: ... + @property + def body_bvhnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_bvhnum.setter + def body_bvhnum(self, arg1: typing.Any) -> None: ... + @property + def body_conaffinity(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_conaffinity.setter + def body_conaffinity(self, arg1: typing.Any) -> None: ... + @property + def body_contype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_contype.setter + def body_contype(self, arg1: typing.Any) -> None: ... + @property + def body_dofadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_dofadr.setter + def body_dofadr(self, arg1: typing.Any) -> None: ... + @property + def body_dofnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_dofnum.setter + def body_dofnum(self, arg1: typing.Any) -> None: ... + @property + def body_geomadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_geomadr.setter + def body_geomadr(self, arg1: typing.Any) -> None: ... + @property + def body_geomnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_geomnum.setter + def body_geomnum(self, arg1: typing.Any) -> None: ... + @property + def body_gravcomp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_gravcomp.setter + def body_gravcomp(self, arg1: typing.Any) -> None: ... + @property + def body_inertia(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_inertia.setter + def body_inertia(self, arg1: typing.Any) -> None: ... + @property + def body_invweight0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_invweight0.setter + def body_invweight0(self, arg1: typing.Any) -> None: ... + @property + def body_ipos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_ipos.setter + def body_ipos(self, arg1: typing.Any) -> None: ... + @property + def body_iquat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_iquat.setter + def body_iquat(self, arg1: typing.Any) -> None: ... + @property + def body_jntadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_jntadr.setter + def body_jntadr(self, arg1: typing.Any) -> None: ... + @property + def body_jntnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_jntnum.setter + def body_jntnum(self, arg1: typing.Any) -> None: ... + @property + def body_margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_margin.setter + def body_margin(self, arg1: typing.Any) -> None: ... + @property + def body_mass(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_mass.setter + def body_mass(self, arg1: typing.Any) -> None: ... + @property + def body_mocapid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_mocapid.setter + def body_mocapid(self, arg1: typing.Any) -> None: ... + @property + def body_parentid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_parentid.setter + def body_parentid(self, arg1: typing.Any) -> None: ... + @property + def body_plugin(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_plugin.setter + def body_plugin(self, arg1: typing.Any) -> None: ... + @property + def body_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_pos.setter + def body_pos(self, arg1: typing.Any) -> None: ... + @property + def body_quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_quat.setter + def body_quat(self, arg1: typing.Any) -> None: ... + @property + def body_rootid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_rootid.setter + def body_rootid(self, arg1: typing.Any) -> None: ... + @property + def body_sameframe(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @body_sameframe.setter + def body_sameframe(self, arg1: typing.Any) -> None: ... + @property + def body_simple(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @body_simple.setter + def body_simple(self, arg1: typing.Any) -> None: ... + @property + def body_subtreemass(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_subtreemass.setter + def body_subtreemass(self, arg1: typing.Any) -> None: ... + @property + def body_treeid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_treeid.setter + def body_treeid(self, arg1: typing.Any) -> None: ... + @property + def body_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @body_user.setter + def body_user(self, arg1: typing.Any) -> None: ... + @property + def body_weldid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @body_weldid.setter + def body_weldid(self, arg1: typing.Any) -> None: ... + @property + def bvh_aabb(self) -> numpy.typing.NDArray[numpy.float64]: ... + @bvh_aabb.setter + def bvh_aabb(self, arg1: typing.Any) -> None: ... + @property + def bvh_child(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bvh_child.setter + def bvh_child(self, arg1: typing.Any) -> None: ... + @property + def bvh_depth(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bvh_depth.setter + def bvh_depth(self, arg1: typing.Any) -> None: ... + @property + def bvh_nodeid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bvh_nodeid.setter + def bvh_nodeid(self, arg1: typing.Any) -> None: ... + @property + def cam_bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @cam_bodyid.setter + def cam_bodyid(self, arg1: typing.Any) -> None: ... + @property + def cam_fovy(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_fovy.setter + def cam_fovy(self, arg1: typing.Any) -> None: ... + @property + def cam_intrinsic(self) -> numpy.typing.NDArray[numpy.float32]: ... + @cam_intrinsic.setter + def cam_intrinsic(self, arg1: typing.Any) -> None: ... + @property + def cam_ipd(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_ipd.setter + def cam_ipd(self, arg1: typing.Any) -> None: ... + @property + def cam_mat0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_mat0.setter + def cam_mat0(self, arg1: typing.Any) -> None: ... + @property + def cam_mode(self) -> numpy.typing.NDArray[numpy.int32]: ... + @cam_mode.setter + def cam_mode(self, arg1: typing.Any) -> None: ... + @property + def cam_orthographic(self) -> numpy.typing.NDArray[numpy.int32]: ... + @cam_orthographic.setter + def cam_orthographic(self, arg1: typing.Any) -> None: ... + @property + def cam_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_pos.setter + def cam_pos(self, arg1: typing.Any) -> None: ... + @property + def cam_pos0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_pos0.setter + def cam_pos0(self, arg1: typing.Any) -> None: ... + @property + def cam_poscom0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_poscom0.setter + def cam_poscom0(self, arg1: typing.Any) -> None: ... + @property + def cam_quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_quat.setter + def cam_quat(self, arg1: typing.Any) -> None: ... + @property + def cam_resolution(self) -> numpy.typing.NDArray[numpy.int32]: ... + @cam_resolution.setter + def cam_resolution(self, arg1: typing.Any) -> None: ... + @property + def cam_sensorsize(self) -> numpy.typing.NDArray[numpy.float32]: ... + @cam_sensorsize.setter + def cam_sensorsize(self, arg1: typing.Any) -> None: ... + @property + def cam_targetbodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @cam_targetbodyid.setter + def cam_targetbodyid(self, arg1: typing.Any) -> None: ... + @property + def cam_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cam_user.setter + def cam_user(self, arg1: typing.Any) -> None: ... + @property + def dof_M0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dof_M0.setter + def dof_M0(self, arg1: typing.Any) -> None: ... + @property + def dof_Madr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dof_Madr.setter + def dof_Madr(self, arg1: typing.Any) -> None: ... + @property + def dof_armature(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dof_armature.setter + def dof_armature(self, arg1: typing.Any) -> None: ... + @property + def dof_bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dof_bodyid.setter + def dof_bodyid(self, arg1: typing.Any) -> None: ... + @property + def dof_damping(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dof_damping.setter + def dof_damping(self, arg1: typing.Any) -> None: ... + @property + def dof_frictionloss(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dof_frictionloss.setter + def dof_frictionloss(self, arg1: typing.Any) -> None: ... + @property + def dof_invweight0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dof_invweight0.setter + def dof_invweight0(self, arg1: typing.Any) -> None: ... + @property + def dof_jntid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dof_jntid.setter + def dof_jntid(self, arg1: typing.Any) -> None: ... + @property + def dof_parentid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dof_parentid.setter + def dof_parentid(self, arg1: typing.Any) -> None: ... + @property + def dof_simplenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dof_simplenum.setter + def dof_simplenum(self, arg1: typing.Any) -> None: ... + @property + def dof_solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dof_solimp.setter + def dof_solimp(self, arg1: typing.Any) -> None: ... + @property + def dof_solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dof_solref.setter + def dof_solref(self, arg1: typing.Any) -> None: ... + @property + def dof_treeid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dof_treeid.setter + def dof_treeid(self, arg1: typing.Any) -> None: ... + @property + def eq_active0(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @eq_active0.setter + def eq_active0(self, arg1: typing.Any) -> None: ... + @property + def eq_data(self) -> numpy.typing.NDArray[numpy.float64]: ... + @eq_data.setter + def eq_data(self, arg1: typing.Any) -> None: ... + @property + def eq_obj1id(self) -> numpy.typing.NDArray[numpy.int32]: ... + @eq_obj1id.setter + def eq_obj1id(self, arg1: typing.Any) -> None: ... + @property + def eq_obj2id(self) -> numpy.typing.NDArray[numpy.int32]: ... + @eq_obj2id.setter + def eq_obj2id(self, arg1: typing.Any) -> None: ... + @property + def eq_objtype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @eq_objtype.setter + def eq_objtype(self, arg1: typing.Any) -> None: ... + @property + def eq_solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @eq_solimp.setter + def eq_solimp(self, arg1: typing.Any) -> None: ... + @property + def eq_solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @eq_solref.setter + def eq_solref(self, arg1: typing.Any) -> None: ... + @property + def eq_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @eq_type.setter + def eq_type(self, arg1: typing.Any) -> None: ... + @property + def exclude_signature(self) -> numpy.typing.NDArray[numpy.int32]: ... + @exclude_signature.setter + def exclude_signature(self, arg1: typing.Any) -> None: ... + @property + def flex_activelayers(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_activelayers.setter + def flex_activelayers(self, arg1: typing.Any) -> None: ... + @property + def flex_bending(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_bending.setter + def flex_bending(self, arg1: typing.Any) -> None: ... + @property + def flex_bvhadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_bvhadr.setter + def flex_bvhadr(self, arg1: typing.Any) -> None: ... + @property + def flex_bvhnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_bvhnum.setter + def flex_bvhnum(self, arg1: typing.Any) -> None: ... + @property + def flex_centered(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flex_centered.setter + def flex_centered(self, arg1: typing.Any) -> None: ... + @property + def flex_conaffinity(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_conaffinity.setter + def flex_conaffinity(self, arg1: typing.Any) -> None: ... + @property + def flex_condim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_condim.setter + def flex_condim(self, arg1: typing.Any) -> None: ... + @property + def flex_contype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_contype.setter + def flex_contype(self, arg1: typing.Any) -> None: ... + @property + def flex_damping(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_damping.setter + def flex_damping(self, arg1: typing.Any) -> None: ... + @property + def flex_dim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_dim.setter + def flex_dim(self, arg1: typing.Any) -> None: ... + @property + def flex_edge(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_edge.setter + def flex_edge(self, arg1: typing.Any) -> None: ... + @property + def flex_edgeadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_edgeadr.setter + def flex_edgeadr(self, arg1: typing.Any) -> None: ... + @property + def flex_edgedamping(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_edgedamping.setter + def flex_edgedamping(self, arg1: typing.Any) -> None: ... + @property + def flex_edgeequality(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flex_edgeequality.setter + def flex_edgeequality(self, arg1: typing.Any) -> None: ... + @property + def flex_edgeflap(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_edgeflap.setter + def flex_edgeflap(self, arg1: typing.Any) -> None: ... + @property + def flex_edgenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_edgenum.setter + def flex_edgenum(self, arg1: typing.Any) -> None: ... + @property + def flex_edgestiffness(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_edgestiffness.setter + def flex_edgestiffness(self, arg1: typing.Any) -> None: ... + @property + def flex_elem(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elem.setter + def flex_elem(self, arg1: typing.Any) -> None: ... + @property + def flex_elemadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elemadr.setter + def flex_elemadr(self, arg1: typing.Any) -> None: ... + @property + def flex_elemdataadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elemdataadr.setter + def flex_elemdataadr(self, arg1: typing.Any) -> None: ... + @property + def flex_elemedge(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elemedge.setter + def flex_elemedge(self, arg1: typing.Any) -> None: ... + @property + def flex_elemedgeadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elemedgeadr.setter + def flex_elemedgeadr(self, arg1: typing.Any) -> None: ... + @property + def flex_elemlayer(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elemlayer.setter + def flex_elemlayer(self, arg1: typing.Any) -> None: ... + @property + def flex_elemnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elemnum.setter + def flex_elemnum(self, arg1: typing.Any) -> None: ... + @property + def flex_elemtexcoord(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_elemtexcoord.setter + def flex_elemtexcoord(self, arg1: typing.Any) -> None: ... + @property + def flex_evpair(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_evpair.setter + def flex_evpair(self, arg1: typing.Any) -> None: ... + @property + def flex_evpairadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_evpairadr.setter + def flex_evpairadr(self, arg1: typing.Any) -> None: ... + @property + def flex_evpairnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_evpairnum.setter + def flex_evpairnum(self, arg1: typing.Any) -> None: ... + @property + def flex_flatskin(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flex_flatskin.setter + def flex_flatskin(self, arg1: typing.Any) -> None: ... + @property + def flex_friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_friction.setter + def flex_friction(self, arg1: typing.Any) -> None: ... + @property + def flex_gap(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_gap.setter + def flex_gap(self, arg1: typing.Any) -> None: ... + @property + def flex_group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_group.setter + def flex_group(self, arg1: typing.Any) -> None: ... + @property + def flex_internal(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flex_internal.setter + def flex_internal(self, arg1: typing.Any) -> None: ... + @property + def flex_interp(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_interp.setter + def flex_interp(self, arg1: typing.Any) -> None: ... + @property + def flex_margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_margin.setter + def flex_margin(self, arg1: typing.Any) -> None: ... + @property + def flex_matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_matid.setter + def flex_matid(self, arg1: typing.Any) -> None: ... + @property + def flex_node(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_node.setter + def flex_node(self, arg1: typing.Any) -> None: ... + @property + def flex_node0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_node0.setter + def flex_node0(self, arg1: typing.Any) -> None: ... + @property + def flex_nodeadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_nodeadr.setter + def flex_nodeadr(self, arg1: typing.Any) -> None: ... + @property + def flex_nodebodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_nodebodyid.setter + def flex_nodebodyid(self, arg1: typing.Any) -> None: ... + @property + def flex_nodenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_nodenum.setter + def flex_nodenum(self, arg1: typing.Any) -> None: ... + @property + def flex_priority(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_priority.setter + def flex_priority(self, arg1: typing.Any) -> None: ... + @property + def flex_radius(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_radius.setter + def flex_radius(self, arg1: typing.Any) -> None: ... + @property + def flex_rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @flex_rgba.setter + def flex_rgba(self, arg1: typing.Any) -> None: ... + @property + def flex_rigid(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flex_rigid.setter + def flex_rigid(self, arg1: typing.Any) -> None: ... + @property + def flex_selfcollide(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_selfcollide.setter + def flex_selfcollide(self, arg1: typing.Any) -> None: ... + @property + def flex_shell(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_shell.setter + def flex_shell(self, arg1: typing.Any) -> None: ... + @property + def flex_shelldataadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_shelldataadr.setter + def flex_shelldataadr(self, arg1: typing.Any) -> None: ... + @property + def flex_shellnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_shellnum.setter + def flex_shellnum(self, arg1: typing.Any) -> None: ... + @property + def flex_solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_solimp.setter + def flex_solimp(self, arg1: typing.Any) -> None: ... + @property + def flex_solmix(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_solmix.setter + def flex_solmix(self, arg1: typing.Any) -> None: ... + @property + def flex_solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_solref.setter + def flex_solref(self, arg1: typing.Any) -> None: ... + @property + def flex_stiffness(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_stiffness.setter + def flex_stiffness(self, arg1: typing.Any) -> None: ... + @property + def flex_texcoord(self) -> numpy.typing.NDArray[numpy.float32]: ... + @flex_texcoord.setter + def flex_texcoord(self, arg1: typing.Any) -> None: ... + @property + def flex_texcoordadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_texcoordadr.setter + def flex_texcoordadr(self, arg1: typing.Any) -> None: ... + @property + def flex_vert(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_vert.setter + def flex_vert(self, arg1: typing.Any) -> None: ... + @property + def flex_vert0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flex_vert0.setter + def flex_vert0(self, arg1: typing.Any) -> None: ... + @property + def flex_vertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_vertadr.setter + def flex_vertadr(self, arg1: typing.Any) -> None: ... + @property + def flex_vertbodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_vertbodyid.setter + def flex_vertbodyid(self, arg1: typing.Any) -> None: ... + @property + def flex_vertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flex_vertnum.setter + def flex_vertnum(self, arg1: typing.Any) -> None: ... + @property + def flexedge_invweight0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flexedge_invweight0.setter + def flexedge_invweight0(self, arg1: typing.Any) -> None: ... + @property + def flexedge_length0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @flexedge_length0.setter + def flexedge_length0(self, arg1: typing.Any) -> None: ... + @property + def flexedge_rigid(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flexedge_rigid.setter + def flexedge_rigid(self, arg1: typing.Any) -> None: ... + @property + def geom_aabb(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_aabb.setter + def geom_aabb(self, arg1: typing.Any) -> None: ... + @property + def geom_bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_bodyid.setter + def geom_bodyid(self, arg1: typing.Any) -> None: ... + @property + def geom_conaffinity(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_conaffinity.setter + def geom_conaffinity(self, arg1: typing.Any) -> None: ... + @property + def geom_condim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_condim.setter + def geom_condim(self, arg1: typing.Any) -> None: ... + @property + def geom_contype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_contype.setter + def geom_contype(self, arg1: typing.Any) -> None: ... + @property + def geom_dataid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_dataid.setter + def geom_dataid(self, arg1: typing.Any) -> None: ... + @property + def geom_fluid(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_fluid.setter + def geom_fluid(self, arg1: typing.Any) -> None: ... + @property + def geom_friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_friction.setter + def geom_friction(self, arg1: typing.Any) -> None: ... + @property + def geom_gap(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_gap.setter + def geom_gap(self, arg1: typing.Any) -> None: ... + @property + def geom_group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_group.setter + def geom_group(self, arg1: typing.Any) -> None: ... + @property + def geom_margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_margin.setter + def geom_margin(self, arg1: typing.Any) -> None: ... + @property + def geom_matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_matid.setter + def geom_matid(self, arg1: typing.Any) -> None: ... + @property + def geom_plugin(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_plugin.setter + def geom_plugin(self, arg1: typing.Any) -> None: ... + @property + def geom_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_pos.setter + def geom_pos(self, arg1: typing.Any) -> None: ... + @property + def geom_priority(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_priority.setter + def geom_priority(self, arg1: typing.Any) -> None: ... + @property + def geom_quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_quat.setter + def geom_quat(self, arg1: typing.Any) -> None: ... + @property + def geom_rbound(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_rbound.setter + def geom_rbound(self, arg1: typing.Any) -> None: ... + @property + def geom_rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @geom_rgba.setter + def geom_rgba(self, arg1: typing.Any) -> None: ... + @property + def geom_sameframe(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @geom_sameframe.setter + def geom_sameframe(self, arg1: typing.Any) -> None: ... + @property + def geom_size(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_size.setter + def geom_size(self, arg1: typing.Any) -> None: ... + @property + def geom_solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_solimp.setter + def geom_solimp(self, arg1: typing.Any) -> None: ... + @property + def geom_solmix(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_solmix.setter + def geom_solmix(self, arg1: typing.Any) -> None: ... + @property + def geom_solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_solref.setter + def geom_solref(self, arg1: typing.Any) -> None: ... + @property + def geom_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom_type.setter + def geom_type(self, arg1: typing.Any) -> None: ... + @property + def geom_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @geom_user.setter + def geom_user(self, arg1: typing.Any) -> None: ... + @property + def hfield_adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @hfield_adr.setter + def hfield_adr(self, arg1: typing.Any) -> None: ... + @property + def hfield_data(self) -> numpy.typing.NDArray[numpy.float32]: ... + @hfield_data.setter + def hfield_data(self, arg1: typing.Any) -> None: ... + @property + def hfield_ncol(self) -> numpy.typing.NDArray[numpy.int32]: ... + @hfield_ncol.setter + def hfield_ncol(self, arg1: typing.Any) -> None: ... + @property + def hfield_nrow(self) -> numpy.typing.NDArray[numpy.int32]: ... + @hfield_nrow.setter + def hfield_nrow(self, arg1: typing.Any) -> None: ... + @property + def hfield_pathadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @hfield_pathadr.setter + def hfield_pathadr(self, arg1: typing.Any) -> None: ... + @property + def hfield_size(self) -> numpy.typing.NDArray[numpy.float64]: ... + @hfield_size.setter + def hfield_size(self, arg1: typing.Any) -> None: ... + @property + def jnt_actfrclimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @jnt_actfrclimited.setter + def jnt_actfrclimited(self, arg1: typing.Any) -> None: ... + @property + def jnt_actfrcrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_actfrcrange.setter + def jnt_actfrcrange(self, arg1: typing.Any) -> None: ... + @property + def jnt_actgravcomp(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @jnt_actgravcomp.setter + def jnt_actgravcomp(self, arg1: typing.Any) -> None: ... + @property + def jnt_axis(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_axis.setter + def jnt_axis(self, arg1: typing.Any) -> None: ... + @property + def jnt_bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jnt_bodyid.setter + def jnt_bodyid(self, arg1: typing.Any) -> None: ... + @property + def jnt_dofadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jnt_dofadr.setter + def jnt_dofadr(self, arg1: typing.Any) -> None: ... + @property + def jnt_group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jnt_group.setter + def jnt_group(self, arg1: typing.Any) -> None: ... + @property + def jnt_limited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @jnt_limited.setter + def jnt_limited(self, arg1: typing.Any) -> None: ... + @property + def jnt_margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_margin.setter + def jnt_margin(self, arg1: typing.Any) -> None: ... + @property + def jnt_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_pos.setter + def jnt_pos(self, arg1: typing.Any) -> None: ... + @property + def jnt_qposadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jnt_qposadr.setter + def jnt_qposadr(self, arg1: typing.Any) -> None: ... + @property + def jnt_range(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_range.setter + def jnt_range(self, arg1: typing.Any) -> None: ... + @property + def jnt_solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_solimp.setter + def jnt_solimp(self, arg1: typing.Any) -> None: ... + @property + def jnt_solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_solref.setter + def jnt_solref(self, arg1: typing.Any) -> None: ... + @property + def jnt_stiffness(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_stiffness.setter + def jnt_stiffness(self, arg1: typing.Any) -> None: ... + @property + def jnt_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jnt_type.setter + def jnt_type(self, arg1: typing.Any) -> None: ... + @property + def jnt_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @jnt_user.setter + def jnt_user(self, arg1: typing.Any) -> None: ... + @property + def key_act(self) -> numpy.typing.NDArray[numpy.float64]: ... + @key_act.setter + def key_act(self, arg1: typing.Any) -> None: ... + @property + def key_ctrl(self) -> numpy.typing.NDArray[numpy.float64]: ... + @key_ctrl.setter + def key_ctrl(self, arg1: typing.Any) -> None: ... + @property + def key_mpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @key_mpos.setter + def key_mpos(self, arg1: typing.Any) -> None: ... + @property + def key_mquat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @key_mquat.setter + def key_mquat(self, arg1: typing.Any) -> None: ... + @property + def key_qpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @key_qpos.setter + def key_qpos(self, arg1: typing.Any) -> None: ... + @property + def key_qvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @key_qvel.setter + def key_qvel(self, arg1: typing.Any) -> None: ... + @property + def key_time(self) -> numpy.typing.NDArray[numpy.float64]: ... + @key_time.setter + def key_time(self, arg1: typing.Any) -> None: ... + @property + def light_active(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @light_active.setter + def light_active(self, arg1: typing.Any) -> None: ... + @property + def light_ambient(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_ambient.setter + def light_ambient(self, arg1: typing.Any) -> None: ... + @property + def light_attenuation(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_attenuation.setter + def light_attenuation(self, arg1: typing.Any) -> None: ... + @property + def light_bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @light_bodyid.setter + def light_bodyid(self, arg1: typing.Any) -> None: ... + @property + def light_bulbradius(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_bulbradius.setter + def light_bulbradius(self, arg1: typing.Any) -> None: ... + @property + def light_castshadow(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @light_castshadow.setter + def light_castshadow(self, arg1: typing.Any) -> None: ... + @property + def light_cutoff(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_cutoff.setter + def light_cutoff(self, arg1: typing.Any) -> None: ... + @property + def light_diffuse(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_diffuse.setter + def light_diffuse(self, arg1: typing.Any) -> None: ... + @property + def light_dir(self) -> numpy.typing.NDArray[numpy.float64]: ... + @light_dir.setter + def light_dir(self, arg1: typing.Any) -> None: ... + @property + def light_dir0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @light_dir0.setter + def light_dir0(self, arg1: typing.Any) -> None: ... + @property + def light_exponent(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_exponent.setter + def light_exponent(self, arg1: typing.Any) -> None: ... + @property + def light_intensity(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_intensity.setter + def light_intensity(self, arg1: typing.Any) -> None: ... + @property + def light_mode(self) -> numpy.typing.NDArray[numpy.int32]: ... + @light_mode.setter + def light_mode(self, arg1: typing.Any) -> None: ... + @property + def light_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @light_pos.setter + def light_pos(self, arg1: typing.Any) -> None: ... + @property + def light_pos0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @light_pos0.setter + def light_pos0(self, arg1: typing.Any) -> None: ... + @property + def light_poscom0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @light_poscom0.setter + def light_poscom0(self, arg1: typing.Any) -> None: ... + @property + def light_range(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_range.setter + def light_range(self, arg1: typing.Any) -> None: ... + @property + def light_specular(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light_specular.setter + def light_specular(self, arg1: typing.Any) -> None: ... + @property + def light_targetbodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @light_targetbodyid.setter + def light_targetbodyid(self, arg1: typing.Any) -> None: ... + @property + def light_texid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @light_texid.setter + def light_texid(self, arg1: typing.Any) -> None: ... + @property + def light_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @light_type.setter + def light_type(self, arg1: typing.Any) -> None: ... + @property + def mapD2M(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mapD2M.setter + def mapD2M(self, arg1: typing.Any) -> None: ... + @property + def mapM2D(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mapM2D.setter + def mapM2D(self, arg1: typing.Any) -> None: ... + @property + def mapM2M(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mapM2M.setter + def mapM2M(self, arg1: typing.Any) -> None: ... + @property + def mat_emission(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_emission.setter + def mat_emission(self, arg1: typing.Any) -> None: ... + @property + def mat_metallic(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_metallic.setter + def mat_metallic(self, arg1: typing.Any) -> None: ... + @property + def mat_reflectance(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_reflectance.setter + def mat_reflectance(self, arg1: typing.Any) -> None: ... + @property + def mat_rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_rgba.setter + def mat_rgba(self, arg1: typing.Any) -> None: ... + @property + def mat_roughness(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_roughness.setter + def mat_roughness(self, arg1: typing.Any) -> None: ... + @property + def mat_shininess(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_shininess.setter + def mat_shininess(self, arg1: typing.Any) -> None: ... + @property + def mat_specular(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_specular.setter + def mat_specular(self, arg1: typing.Any) -> None: ... + @property + def mat_texid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mat_texid.setter + def mat_texid(self, arg1: typing.Any) -> None: ... + @property + def mat_texrepeat(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat_texrepeat.setter + def mat_texrepeat(self, arg1: typing.Any) -> None: ... + @property + def mat_texuniform(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @mat_texuniform.setter + def mat_texuniform(self, arg1: typing.Any) -> None: ... + @property + def mesh_bvhadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_bvhadr.setter + def mesh_bvhadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_bvhnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_bvhnum.setter + def mesh_bvhnum(self, arg1: typing.Any) -> None: ... + @property + def mesh_face(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_face.setter + def mesh_face(self, arg1: typing.Any) -> None: ... + @property + def mesh_faceadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_faceadr.setter + def mesh_faceadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_facenormal(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_facenormal.setter + def mesh_facenormal(self, arg1: typing.Any) -> None: ... + @property + def mesh_facenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_facenum.setter + def mesh_facenum(self, arg1: typing.Any) -> None: ... + @property + def mesh_facetexcoord(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_facetexcoord.setter + def mesh_facetexcoord(self, arg1: typing.Any) -> None: ... + @property + def mesh_graph(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_graph.setter + def mesh_graph(self, arg1: typing.Any) -> None: ... + @property + def mesh_graphadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_graphadr.setter + def mesh_graphadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_normal(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mesh_normal.setter + def mesh_normal(self, arg1: typing.Any) -> None: ... + @property + def mesh_normaladr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_normaladr.setter + def mesh_normaladr(self, arg1: typing.Any) -> None: ... + @property + def mesh_normalnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_normalnum.setter + def mesh_normalnum(self, arg1: typing.Any) -> None: ... + @property + def mesh_octadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_octadr.setter + def mesh_octadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_octnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_octnum.setter + def mesh_octnum(self, arg1: typing.Any) -> None: ... + @property + def mesh_pathadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_pathadr.setter + def mesh_pathadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_polyadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polyadr.setter + def mesh_polyadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_polymap(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polymap.setter + def mesh_polymap(self, arg1: typing.Any) -> None: ... + @property + def mesh_polymapadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polymapadr.setter + def mesh_polymapadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_polymapnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polymapnum.setter + def mesh_polymapnum(self, arg1: typing.Any) -> None: ... + @property + def mesh_polynormal(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mesh_polynormal.setter + def mesh_polynormal(self, arg1: typing.Any) -> None: ... + @property + def mesh_polynum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polynum.setter + def mesh_polynum(self, arg1: typing.Any) -> None: ... + @property + def mesh_polyvert(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polyvert.setter + def mesh_polyvert(self, arg1: typing.Any) -> None: ... + @property + def mesh_polyvertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polyvertadr.setter + def mesh_polyvertadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_polyvertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_polyvertnum.setter + def mesh_polyvertnum(self, arg1: typing.Any) -> None: ... + @property + def mesh_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mesh_pos.setter + def mesh_pos(self, arg1: typing.Any) -> None: ... + @property + def mesh_quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mesh_quat.setter + def mesh_quat(self, arg1: typing.Any) -> None: ... + @property + def mesh_scale(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mesh_scale.setter + def mesh_scale(self, arg1: typing.Any) -> None: ... + @property + def mesh_texcoord(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mesh_texcoord.setter + def mesh_texcoord(self, arg1: typing.Any) -> None: ... + @property + def mesh_texcoordadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_texcoordadr.setter + def mesh_texcoordadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_texcoordnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_texcoordnum.setter + def mesh_texcoordnum(self, arg1: typing.Any) -> None: ... + @property + def mesh_vert(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mesh_vert.setter + def mesh_vert(self, arg1: typing.Any) -> None: ... + @property + def mesh_vertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_vertadr.setter + def mesh_vertadr(self, arg1: typing.Any) -> None: ... + @property + def mesh_vertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mesh_vertnum.setter + def mesh_vertnum(self, arg1: typing.Any) -> None: ... + @property + def nB(self) -> int: ... + @property + def nC(self) -> int: ... + @property + def nD(self) -> int: ... + @property + def nJmom(self) -> int: ... + @property + def nM(self) -> int: ... + @property + def na(self) -> int: ... + @property + def name_actuatoradr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_actuatoradr.setter + def name_actuatoradr(self, arg1: typing.Any) -> None: ... + @property + def name_bodyadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_bodyadr.setter + def name_bodyadr(self, arg1: typing.Any) -> None: ... + @property + def name_camadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_camadr.setter + def name_camadr(self, arg1: typing.Any) -> None: ... + @property + def name_eqadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_eqadr.setter + def name_eqadr(self, arg1: typing.Any) -> None: ... + @property + def name_excludeadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_excludeadr.setter + def name_excludeadr(self, arg1: typing.Any) -> None: ... + @property + def name_flexadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_flexadr.setter + def name_flexadr(self, arg1: typing.Any) -> None: ... + @property + def name_geomadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_geomadr.setter + def name_geomadr(self, arg1: typing.Any) -> None: ... + @property + def name_hfieldadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_hfieldadr.setter + def name_hfieldadr(self, arg1: typing.Any) -> None: ... + @property + def name_jntadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_jntadr.setter + def name_jntadr(self, arg1: typing.Any) -> None: ... + @property + def name_keyadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_keyadr.setter + def name_keyadr(self, arg1: typing.Any) -> None: ... + @property + def name_lightadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_lightadr.setter + def name_lightadr(self, arg1: typing.Any) -> None: ... + @property + def name_matadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_matadr.setter + def name_matadr(self, arg1: typing.Any) -> None: ... + @property + def name_meshadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_meshadr.setter + def name_meshadr(self, arg1: typing.Any) -> None: ... + @property + def name_numericadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_numericadr.setter + def name_numericadr(self, arg1: typing.Any) -> None: ... + @property + def name_pairadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_pairadr.setter + def name_pairadr(self, arg1: typing.Any) -> None: ... + @property + def name_pluginadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_pluginadr.setter + def name_pluginadr(self, arg1: typing.Any) -> None: ... + @property + def name_sensoradr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_sensoradr.setter + def name_sensoradr(self, arg1: typing.Any) -> None: ... + @property + def name_siteadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_siteadr.setter + def name_siteadr(self, arg1: typing.Any) -> None: ... + @property + def name_skinadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_skinadr.setter + def name_skinadr(self, arg1: typing.Any) -> None: ... + @property + def name_tendonadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_tendonadr.setter + def name_tendonadr(self, arg1: typing.Any) -> None: ... + @property + def name_texadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_texadr.setter + def name_texadr(self, arg1: typing.Any) -> None: ... + @property + def name_textadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_textadr.setter + def name_textadr(self, arg1: typing.Any) -> None: ... + @property + def name_tupleadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @name_tupleadr.setter + def name_tupleadr(self, arg1: typing.Any) -> None: ... + @property + def names(self) -> bytes: ... + @property + def names_map(self) -> numpy.typing.NDArray[numpy.int32]: ... + @names_map.setter + def names_map(self, arg1: typing.Any) -> None: ... + @property + def narena(self) -> int: ... + @property + def nbody(self) -> int: ... + @property + def nbuffer(self) -> int: ... + @property + def nbvh(self) -> int: ... + @property + def nbvhdynamic(self) -> int: ... + @property + def nbvhstatic(self) -> int: ... + @property + def ncam(self) -> int: ... + @property + def nconmax(self) -> int: ... + @property + def nemax(self) -> int: ... + @property + def neq(self) -> int: ... + @property + def nexclude(self) -> int: ... + @property + def nflex(self) -> int: ... + @property + def nflexedge(self) -> int: ... + @property + def nflexelem(self) -> int: ... + @property + def nflexelemdata(self) -> int: ... + @property + def nflexelemedge(self) -> int: ... + @property + def nflexevpair(self) -> int: ... + @property + def nflexnode(self) -> int: ... + @property + def nflexshelldata(self) -> int: ... + @property + def nflextexcoord(self) -> int: ... + @property + def nflexvert(self) -> int: ... + @property + def ngeom(self) -> int: ... + @property + def ngravcomp(self) -> int: ... + @property + def nhfield(self) -> int: ... + @property + def nhfielddata(self) -> int: ... + @property + def njmax(self) -> int: ... + @property + def njnt(self) -> int: ... + @property + def nkey(self) -> int: ... + @property + def nlight(self) -> int: ... + @property + def nmat(self) -> int: ... + @property + def nmesh(self) -> int: ... + @property + def nmeshface(self) -> int: ... + @property + def nmeshgraph(self) -> int: ... + @property + def nmeshnormal(self) -> int: ... + @property + def nmeshpoly(self) -> int: ... + @property + def nmeshpolymap(self) -> int: ... + @property + def nmeshpolyvert(self) -> int: ... + @property + def nmeshtexcoord(self) -> int: ... + @property + def nmeshvert(self) -> int: ... + @property + def nmocap(self) -> int: ... + @property + def nnames(self) -> int: ... + @property + def nnames_map(self) -> int: ... + @property + def nnumeric(self) -> int: ... + @property + def nnumericdata(self) -> int: ... + @property + def noct(self) -> int: ... + @property + def npair(self) -> int: ... + @property + def npaths(self) -> int: ... + @property + def nplugin(self) -> int: ... + @property + def npluginattr(self) -> int: ... + @property + def npluginstate(self) -> int: ... + @property + def nq(self) -> int: ... + @property + def nsensor(self) -> int: ... + @property + def nsensordata(self) -> int: ... + @property + def nsite(self) -> int: ... + @property + def nskin(self) -> int: ... + @property + def nskinbone(self) -> int: ... + @property + def nskinbonevert(self) -> int: ... + @property + def nskinface(self) -> int: ... + @property + def nskintexvert(self) -> int: ... + @property + def nskinvert(self) -> int: ... + @property + def ntendon(self) -> int: ... + @property + def ntex(self) -> int: ... + @property + def ntexdata(self) -> int: ... + @property + def ntext(self) -> int: ... + @property + def ntextdata(self) -> int: ... + @property + def ntree(self) -> int: ... + @property + def ntuple(self) -> int: ... + @property + def ntupledata(self) -> int: ... + @property + def nu(self) -> int: ... + @property + def numeric_adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @numeric_adr.setter + def numeric_adr(self, arg1: typing.Any) -> None: ... + @property + def numeric_data(self) -> numpy.typing.NDArray[numpy.float64]: ... + @numeric_data.setter + def numeric_data(self, arg1: typing.Any) -> None: ... + @property + def numeric_size(self) -> numpy.typing.NDArray[numpy.int32]: ... + @numeric_size.setter + def numeric_size(self, arg1: typing.Any) -> None: ... + @property + def nuser_actuator(self) -> int: ... + @property + def nuser_body(self) -> int: ... + @property + def nuser_cam(self) -> int: ... + @property + def nuser_geom(self) -> int: ... + @property + def nuser_jnt(self) -> int: ... + @property + def nuser_sensor(self) -> int: ... + @property + def nuser_site(self) -> int: ... + @property + def nuser_tendon(self) -> int: ... + @property + def nuserdata(self) -> int: ... + @property + def nv(self) -> int: ... + @property + def nwrap(self) -> int: ... + @property + def oct_aabb(self) -> numpy.typing.NDArray[numpy.float64]: ... + @oct_aabb.setter + def oct_aabb(self, arg1: typing.Any) -> None: ... + @property + def oct_child(self) -> numpy.typing.NDArray[numpy.int32]: ... + @oct_child.setter + def oct_child(self, arg1: typing.Any) -> None: ... + @property + def oct_coeff(self) -> numpy.typing.NDArray[numpy.float64]: ... + @oct_coeff.setter + def oct_coeff(self, arg1: typing.Any) -> None: ... + @property + def oct_depth(self) -> numpy.typing.NDArray[numpy.int32]: ... + @oct_depth.setter + def oct_depth(self, arg1: typing.Any) -> None: ... + @property + def opt(self) -> MjOption: ... + @property + def pair_dim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @pair_dim.setter + def pair_dim(self, arg1: typing.Any) -> None: ... + @property + def pair_friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pair_friction.setter + def pair_friction(self, arg1: typing.Any) -> None: ... + @property + def pair_gap(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pair_gap.setter + def pair_gap(self, arg1: typing.Any) -> None: ... + @property + def pair_geom1(self) -> numpy.typing.NDArray[numpy.int32]: ... + @pair_geom1.setter + def pair_geom1(self, arg1: typing.Any) -> None: ... + @property + def pair_geom2(self) -> numpy.typing.NDArray[numpy.int32]: ... + @pair_geom2.setter + def pair_geom2(self, arg1: typing.Any) -> None: ... + @property + def pair_margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pair_margin.setter + def pair_margin(self, arg1: typing.Any) -> None: ... + @property + def pair_signature(self) -> numpy.typing.NDArray[numpy.int32]: ... + @pair_signature.setter + def pair_signature(self, arg1: typing.Any) -> None: ... + @property + def pair_solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pair_solimp.setter + def pair_solimp(self, arg1: typing.Any) -> None: ... + @property + def pair_solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pair_solref.setter + def pair_solref(self, arg1: typing.Any) -> None: ... + @property + def pair_solreffriction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pair_solreffriction.setter + def pair_solreffriction(self, arg1: typing.Any) -> None: ... + @property + def paths(self) -> bytes: ... + @property + def plugin(self) -> numpy.typing.NDArray[numpy.int32]: ... + @plugin.setter + def plugin(self, arg1: typing.Any) -> None: ... + @property + def plugin_attr(self) -> numpy.typing.NDArray[numpy.int8]: ... + @plugin_attr.setter + def plugin_attr(self, arg1: typing.Any) -> None: ... + @property + def plugin_attradr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @plugin_attradr.setter + def plugin_attradr(self, arg1: typing.Any) -> None: ... + @property + def plugin_stateadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @plugin_stateadr.setter + def plugin_stateadr(self, arg1: typing.Any) -> None: ... + @property + def plugin_statenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @plugin_statenum.setter + def plugin_statenum(self, arg1: typing.Any) -> None: ... + @property + def qpos0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qpos0.setter + def qpos0(self, arg1: typing.Any) -> None: ... + @property + def qpos_spring(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qpos_spring.setter + def qpos_spring(self, arg1: typing.Any) -> None: ... + @property + def sensor_adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_adr.setter + def sensor_adr(self, arg1: typing.Any) -> None: ... + @property + def sensor_cutoff(self) -> numpy.typing.NDArray[numpy.float64]: ... + @sensor_cutoff.setter + def sensor_cutoff(self, arg1: typing.Any) -> None: ... + @property + def sensor_datatype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_datatype.setter + def sensor_datatype(self, arg1: typing.Any) -> None: ... + @property + def sensor_dim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_dim.setter + def sensor_dim(self, arg1: typing.Any) -> None: ... + @property + def sensor_intprm(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_intprm.setter + def sensor_intprm(self, arg1: typing.Any) -> None: ... + @property + def sensor_needstage(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_needstage.setter + def sensor_needstage(self, arg1: typing.Any) -> None: ... + @property + def sensor_noise(self) -> numpy.typing.NDArray[numpy.float64]: ... + @sensor_noise.setter + def sensor_noise(self, arg1: typing.Any) -> None: ... + @property + def sensor_objid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_objid.setter + def sensor_objid(self, arg1: typing.Any) -> None: ... + @property + def sensor_objtype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_objtype.setter + def sensor_objtype(self, arg1: typing.Any) -> None: ... + @property + def sensor_plugin(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_plugin.setter + def sensor_plugin(self, arg1: typing.Any) -> None: ... + @property + def sensor_refid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_refid.setter + def sensor_refid(self, arg1: typing.Any) -> None: ... + @property + def sensor_reftype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_reftype.setter + def sensor_reftype(self, arg1: typing.Any) -> None: ... + @property + def sensor_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @sensor_type.setter + def sensor_type(self, arg1: typing.Any) -> None: ... + @property + def sensor_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @sensor_user.setter + def sensor_user(self, arg1: typing.Any) -> None: ... + @property + def signature(self) -> int: ... + @property + def site_bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @site_bodyid.setter + def site_bodyid(self, arg1: typing.Any) -> None: ... + @property + def site_group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @site_group.setter + def site_group(self, arg1: typing.Any) -> None: ... + @property + def site_matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @site_matid.setter + def site_matid(self, arg1: typing.Any) -> None: ... + @property + def site_pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @site_pos.setter + def site_pos(self, arg1: typing.Any) -> None: ... + @property + def site_quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @site_quat.setter + def site_quat(self, arg1: typing.Any) -> None: ... + @property + def site_rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @site_rgba.setter + def site_rgba(self, arg1: typing.Any) -> None: ... + @property + def site_sameframe(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @site_sameframe.setter + def site_sameframe(self, arg1: typing.Any) -> None: ... + @property + def site_size(self) -> numpy.typing.NDArray[numpy.float64]: ... + @site_size.setter + def site_size(self, arg1: typing.Any) -> None: ... + @property + def site_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @site_type.setter + def site_type(self, arg1: typing.Any) -> None: ... + @property + def site_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @site_user.setter + def site_user(self, arg1: typing.Any) -> None: ... + @property + def skin_boneadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_boneadr.setter + def skin_boneadr(self, arg1: typing.Any) -> None: ... + @property + def skin_bonebindpos(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skin_bonebindpos.setter + def skin_bonebindpos(self, arg1: typing.Any) -> None: ... + @property + def skin_bonebindquat(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skin_bonebindquat.setter + def skin_bonebindquat(self, arg1: typing.Any) -> None: ... + @property + def skin_bonebodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_bonebodyid.setter + def skin_bonebodyid(self, arg1: typing.Any) -> None: ... + @property + def skin_bonenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_bonenum.setter + def skin_bonenum(self, arg1: typing.Any) -> None: ... + @property + def skin_bonevertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_bonevertadr.setter + def skin_bonevertadr(self, arg1: typing.Any) -> None: ... + @property + def skin_bonevertid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_bonevertid.setter + def skin_bonevertid(self, arg1: typing.Any) -> None: ... + @property + def skin_bonevertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_bonevertnum.setter + def skin_bonevertnum(self, arg1: typing.Any) -> None: ... + @property + def skin_bonevertweight(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skin_bonevertweight.setter + def skin_bonevertweight(self, arg1: typing.Any) -> None: ... + @property + def skin_face(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_face.setter + def skin_face(self, arg1: typing.Any) -> None: ... + @property + def skin_faceadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_faceadr.setter + def skin_faceadr(self, arg1: typing.Any) -> None: ... + @property + def skin_facenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_facenum.setter + def skin_facenum(self, arg1: typing.Any) -> None: ... + @property + def skin_group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_group.setter + def skin_group(self, arg1: typing.Any) -> None: ... + @property + def skin_inflate(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skin_inflate.setter + def skin_inflate(self, arg1: typing.Any) -> None: ... + @property + def skin_matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_matid.setter + def skin_matid(self, arg1: typing.Any) -> None: ... + @property + def skin_pathadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_pathadr.setter + def skin_pathadr(self, arg1: typing.Any) -> None: ... + @property + def skin_rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skin_rgba.setter + def skin_rgba(self, arg1: typing.Any) -> None: ... + @property + def skin_texcoord(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skin_texcoord.setter + def skin_texcoord(self, arg1: typing.Any) -> None: ... + @property + def skin_texcoordadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_texcoordadr.setter + def skin_texcoordadr(self, arg1: typing.Any) -> None: ... + @property + def skin_vert(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skin_vert.setter + def skin_vert(self, arg1: typing.Any) -> None: ... + @property + def skin_vertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_vertadr.setter + def skin_vertadr(self, arg1: typing.Any) -> None: ... + @property + def skin_vertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skin_vertnum.setter + def skin_vertnum(self, arg1: typing.Any) -> None: ... + @property + def stat(self) -> ...: ... + @property + def tendon_actfrclimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @tendon_actfrclimited.setter + def tendon_actfrclimited(self, arg1: typing.Any) -> None: ... + @property + def tendon_actfrcrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_actfrcrange.setter + def tendon_actfrcrange(self, arg1: typing.Any) -> None: ... + @property + def tendon_adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tendon_adr.setter + def tendon_adr(self, arg1: typing.Any) -> None: ... + @property + def tendon_armature(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_armature.setter + def tendon_armature(self, arg1: typing.Any) -> None: ... + @property + def tendon_damping(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_damping.setter + def tendon_damping(self, arg1: typing.Any) -> None: ... + @property + def tendon_frictionloss(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_frictionloss.setter + def tendon_frictionloss(self, arg1: typing.Any) -> None: ... + @property + def tendon_group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tendon_group.setter + def tendon_group(self, arg1: typing.Any) -> None: ... + @property + def tendon_invweight0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_invweight0.setter + def tendon_invweight0(self, arg1: typing.Any) -> None: ... + @property + def tendon_length0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_length0.setter + def tendon_length0(self, arg1: typing.Any) -> None: ... + @property + def tendon_lengthspring(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_lengthspring.setter + def tendon_lengthspring(self, arg1: typing.Any) -> None: ... + @property + def tendon_limited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @tendon_limited.setter + def tendon_limited(self, arg1: typing.Any) -> None: ... + @property + def tendon_margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_margin.setter + def tendon_margin(self, arg1: typing.Any) -> None: ... + @property + def tendon_matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tendon_matid.setter + def tendon_matid(self, arg1: typing.Any) -> None: ... + @property + def tendon_num(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tendon_num.setter + def tendon_num(self, arg1: typing.Any) -> None: ... + @property + def tendon_range(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_range.setter + def tendon_range(self, arg1: typing.Any) -> None: ... + @property + def tendon_rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @tendon_rgba.setter + def tendon_rgba(self, arg1: typing.Any) -> None: ... + @property + def tendon_solimp_fri(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_solimp_fri.setter + def tendon_solimp_fri(self, arg1: typing.Any) -> None: ... + @property + def tendon_solimp_lim(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_solimp_lim.setter + def tendon_solimp_lim(self, arg1: typing.Any) -> None: ... + @property + def tendon_solref_fri(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_solref_fri.setter + def tendon_solref_fri(self, arg1: typing.Any) -> None: ... + @property + def tendon_solref_lim(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_solref_lim.setter + def tendon_solref_lim(self, arg1: typing.Any) -> None: ... + @property + def tendon_stiffness(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_stiffness.setter + def tendon_stiffness(self, arg1: typing.Any) -> None: ... + @property + def tendon_user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_user.setter + def tendon_user(self, arg1: typing.Any) -> None: ... + @property + def tendon_width(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tendon_width.setter + def tendon_width(self, arg1: typing.Any) -> None: ... + @property + def tex_adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tex_adr.setter + def tex_adr(self, arg1: typing.Any) -> None: ... + @property + def tex_colorspace(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tex_colorspace.setter + def tex_colorspace(self, arg1: typing.Any) -> None: ... + @property + def tex_data(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @tex_data.setter + def tex_data(self, arg1: typing.Any) -> None: ... + @property + def tex_height(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tex_height.setter + def tex_height(self, arg1: typing.Any) -> None: ... + @property + def tex_nchannel(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tex_nchannel.setter + def tex_nchannel(self, arg1: typing.Any) -> None: ... + @property + def tex_pathadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tex_pathadr.setter + def tex_pathadr(self, arg1: typing.Any) -> None: ... + @property + def tex_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tex_type.setter + def tex_type(self, arg1: typing.Any) -> None: ... + @property + def tex_width(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tex_width.setter + def tex_width(self, arg1: typing.Any) -> None: ... + @property + def text_adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @text_adr.setter + def text_adr(self, arg1: typing.Any) -> None: ... + @property + def text_data(self) -> bytes: ... + @property + def text_size(self) -> numpy.typing.NDArray[numpy.int32]: ... + @text_size.setter + def text_size(self, arg1: typing.Any) -> None: ... + @property + def tuple_adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tuple_adr.setter + def tuple_adr(self, arg1: typing.Any) -> None: ... + @property + def tuple_objid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tuple_objid.setter + def tuple_objid(self, arg1: typing.Any) -> None: ... + @property + def tuple_objprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @tuple_objprm.setter + def tuple_objprm(self, arg1: typing.Any) -> None: ... + @property + def tuple_objtype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tuple_objtype.setter + def tuple_objtype(self, arg1: typing.Any) -> None: ... + @property + def tuple_size(self) -> numpy.typing.NDArray[numpy.int32]: ... + @tuple_size.setter + def tuple_size(self, arg1: typing.Any) -> None: ... + @property + def vis(self) -> MjVisual: ... + @property + def wrap_objid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @wrap_objid.setter + def wrap_objid(self, arg1: typing.Any) -> None: ... + @property + def wrap_prm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @wrap_prm.setter + def wrap_prm(self, arg1: typing.Any) -> None: ... + @property + def wrap_type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @wrap_type.setter + def wrap_type(self, arg1: typing.Any) -> None: ... + +class MjOption: + __hash__: typing.ClassVar[None] = None + _float_fields: typing.ClassVar[tuple] = ( + "timestep", + "apirate", + "impratio", + "tolerance", + "ls_tolerance", + "noslip_tolerance", + "ccd_tolerance", + "density", + "viscosity", + "o_margin", + ) + _floatarray_fields: typing.ClassVar[tuple] = ( + "gravity", + "wind", + "magnetic", + "o_solref", + "o_solimp", + "o_friction", + ) + _int_fields: typing.ClassVar[tuple] = ( + "integrator", + "cone", + "jacobian", + "solver", + "iterations", + "ls_iterations", + "noslip_iterations", + "ccd_iterations", + "disableflags", + "enableflags", + "disableactuator", + "sdf_initpoints", + "sdf_iterations", + ) + def __copy__(self) -> MjOption: ... + def __deepcopy__(self, arg0: dict) -> MjOption: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def apirate(self) -> float: ... + @apirate.setter + def apirate(self, arg1: typing.SupportsFloat) -> None: ... + @property + def ccd_iterations(self) -> int: ... + @ccd_iterations.setter + def ccd_iterations(self, arg1: typing.SupportsInt) -> None: ... + @property + def ccd_tolerance(self) -> float: ... + @ccd_tolerance.setter + def ccd_tolerance(self, arg1: typing.SupportsFloat) -> None: ... + @property + def cone(self) -> int: ... + @cone.setter + def cone(self, arg1: typing.SupportsInt) -> None: ... + @property + def density(self) -> float: ... + @density.setter + def density(self, arg1: typing.SupportsFloat) -> None: ... + @property + def disableactuator(self) -> int: ... + @disableactuator.setter + def disableactuator(self, arg1: typing.SupportsInt) -> None: ... + @property + def disableflags(self) -> int: ... + @disableflags.setter + def disableflags(self, arg1: typing.SupportsInt) -> None: ... + @property + def enableflags(self) -> int: ... + @enableflags.setter + def enableflags(self, arg1: typing.SupportsInt) -> None: ... + @property + def gravity(self) -> numpy.typing.NDArray[numpy.float64]: ... + @gravity.setter + def gravity(self, arg1: typing.Any) -> None: ... + @property + def impratio(self) -> float: ... + @impratio.setter + def impratio(self, arg1: typing.SupportsFloat) -> None: ... + @property + def integrator(self) -> int: ... + @integrator.setter + def integrator(self, arg1: typing.SupportsInt) -> None: ... + @property + def iterations(self) -> int: ... + @iterations.setter + def iterations(self, arg1: typing.SupportsInt) -> None: ... + @property + def jacobian(self) -> int: ... + @jacobian.setter + def jacobian(self, arg1: typing.SupportsInt) -> None: ... + @property + def ls_iterations(self) -> int: ... + @ls_iterations.setter + def ls_iterations(self, arg1: typing.SupportsInt) -> None: ... + @property + def ls_tolerance(self) -> float: ... + @ls_tolerance.setter + def ls_tolerance(self, arg1: typing.SupportsFloat) -> None: ... + @property + def magnetic(self) -> numpy.typing.NDArray[numpy.float64]: ... + @magnetic.setter + def magnetic(self, arg1: typing.Any) -> None: ... + @property + def noslip_iterations(self) -> int: ... + @noslip_iterations.setter + def noslip_iterations(self, arg1: typing.SupportsInt) -> None: ... + @property + def noslip_tolerance(self) -> float: ... + @noslip_tolerance.setter + def noslip_tolerance(self, arg1: typing.SupportsFloat) -> None: ... + @property + def o_friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @o_friction.setter + def o_friction(self, arg1: typing.Any) -> None: ... + @property + def o_margin(self) -> float: ... + @o_margin.setter + def o_margin(self, arg1: typing.SupportsFloat) -> None: ... + @property + def o_solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @o_solimp.setter + def o_solimp(self, arg1: typing.Any) -> None: ... + @property + def o_solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @o_solref.setter + def o_solref(self, arg1: typing.Any) -> None: ... + @property + def sdf_initpoints(self) -> int: ... + @sdf_initpoints.setter + def sdf_initpoints(self, arg1: typing.SupportsInt) -> None: ... + @property + def sdf_iterations(self) -> int: ... + @sdf_iterations.setter + def sdf_iterations(self, arg1: typing.SupportsInt) -> None: ... + @property + def solver(self) -> int: ... + @solver.setter + def solver(self, arg1: typing.SupportsInt) -> None: ... + @property + def timestep(self) -> float: ... + @timestep.setter + def timestep(self, arg1: typing.SupportsFloat) -> None: ... + @property + def tolerance(self) -> float: ... + @tolerance.setter + def tolerance(self, arg1: typing.SupportsFloat) -> None: ... + @property + def viscosity(self) -> float: ... + @viscosity.setter + def viscosity(self, arg1: typing.SupportsFloat) -> None: ... + @property + def wind(self) -> numpy.typing.NDArray[numpy.float64]: ... + @wind.setter + def wind(self, arg1: typing.Any) -> None: ... + +class MjSolverStat: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjSolverStat: ... + def __deepcopy__(self, arg0: dict) -> MjSolverStat: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def gradient(self) -> float: ... + @gradient.setter + def gradient(self, arg1: typing.SupportsFloat) -> None: ... + @property + def improvement(self) -> float: ... + @improvement.setter + def improvement(self, arg1: typing.SupportsFloat) -> None: ... + @property + def lineslope(self) -> float: ... + @lineslope.setter + def lineslope(self, arg1: typing.SupportsFloat) -> None: ... + @property + def nactive(self) -> int: ... + @nactive.setter + def nactive(self, arg1: typing.SupportsInt) -> None: ... + @property + def nchange(self) -> int: ... + @nchange.setter + def nchange(self, arg1: typing.SupportsInt) -> None: ... + @property + def neval(self) -> int: ... + @neval.setter + def neval(self, arg1: typing.SupportsInt) -> None: ... + @property + def nupdate(self) -> int: ... + @nupdate.setter + def nupdate(self, arg1: typing.SupportsInt) -> None: ... + +class MjStatistic: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjStatistic: ... + def __deepcopy__(self, arg0: dict) -> MjStatistic: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def center(self) -> numpy.typing.NDArray[numpy.float64]: ... + @center.setter + def center(self, arg1: typing.Any) -> None: ... + @property + def extent(self) -> float: ... + @extent.setter + def extent(self, arg1: typing.SupportsFloat) -> None: ... + @property + def meaninertia(self) -> float: ... + @meaninertia.setter + def meaninertia(self, arg1: typing.SupportsFloat) -> None: ... + @property + def meanmass(self) -> float: ... + @meanmass.setter + def meanmass(self, arg1: typing.SupportsFloat) -> None: ... + @property + def meansize(self) -> float: ... + @meansize.setter + def meansize(self, arg1: typing.SupportsFloat) -> None: ... + +class MjTimerStat: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjTimerStat: ... + def __deepcopy__(self, arg0: dict) -> MjTimerStat: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def duration(self) -> float: ... + @duration.setter + def duration(self, arg1: typing.SupportsFloat) -> None: ... + @property + def number(self) -> int: ... + @number.setter + def number(self, arg1: typing.SupportsInt) -> None: ... + +class MjVisual: + class Global: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjVisual.Global: ... + def __deepcopy__(self, arg0: dict) -> MjVisual.Global: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __repr__(self) -> str: ... + @property + def azimuth(self) -> float: ... + @azimuth.setter + def azimuth(self, arg0: typing.SupportsFloat) -> None: ... + @property + def bvactive(self) -> int: ... + @bvactive.setter + def bvactive(self, arg0: typing.SupportsInt) -> None: ... + @property + def cameraid(self) -> int: ... + @cameraid.setter + def cameraid(self, arg0: typing.SupportsInt) -> None: ... + @property + def elevation(self) -> float: ... + @elevation.setter + def elevation(self, arg0: typing.SupportsFloat) -> None: ... + @property + def ellipsoidinertia(self) -> int: ... + @ellipsoidinertia.setter + def ellipsoidinertia(self, arg0: typing.SupportsInt) -> None: ... + @property + def fovy(self) -> float: ... + @fovy.setter + def fovy(self, arg0: typing.SupportsFloat) -> None: ... + @property + def glow(self) -> float: ... + @glow.setter + def glow(self, arg0: typing.SupportsFloat) -> None: ... + @property + def ipd(self) -> float: ... + @ipd.setter + def ipd(self, arg0: typing.SupportsFloat) -> None: ... + @property + def linewidth(self) -> float: ... + @linewidth.setter + def linewidth(self, arg0: typing.SupportsFloat) -> None: ... + @property + def offheight(self) -> int: ... + @offheight.setter + def offheight(self, arg0: typing.SupportsInt) -> None: ... + @property + def offwidth(self) -> int: ... + @offwidth.setter + def offwidth(self, arg0: typing.SupportsInt) -> None: ... + @property + def orthographic(self) -> int: ... + @orthographic.setter + def orthographic(self, arg0: typing.SupportsInt) -> None: ... + @property + def realtime(self) -> float: ... + @realtime.setter + def realtime(self, arg0: typing.SupportsFloat) -> None: ... + + class Headlight: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjVisual.Headlight: ... + def __deepcopy__(self, arg0: dict) -> MjVisual.Headlight: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __repr__(self) -> str: ... + @property + def active(self) -> int: ... + @active.setter + def active(self, arg1: typing.SupportsInt) -> int: ... + @property + def ambient(self) -> numpy.typing.NDArray[numpy.float32]: ... + @ambient.setter + def ambient(self, arg1: typing.Any) -> None: ... + @property + def diffuse(self) -> numpy.typing.NDArray[numpy.float32]: ... + @diffuse.setter + def diffuse(self, arg1: typing.Any) -> None: ... + @property + def specular(self) -> numpy.typing.NDArray[numpy.float32]: ... + @specular.setter + def specular(self, arg1: typing.Any) -> None: ... + + class Map: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjVisual.Map: ... + def __deepcopy__(self, arg0: dict) -> MjVisual.Map: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __repr__(self) -> str: ... + @property + def actuatortendon(self) -> float: ... + @actuatortendon.setter + def actuatortendon(self, arg0: typing.SupportsFloat) -> None: ... + @property + def alpha(self) -> float: ... + @alpha.setter + def alpha(self, arg0: typing.SupportsFloat) -> None: ... + @property + def fogend(self) -> float: ... + @fogend.setter + def fogend(self, arg0: typing.SupportsFloat) -> None: ... + @property + def fogstart(self) -> float: ... + @fogstart.setter + def fogstart(self, arg0: typing.SupportsFloat) -> None: ... + @property + def force(self) -> float: ... + @force.setter + def force(self, arg0: typing.SupportsFloat) -> None: ... + @property + def haze(self) -> float: ... + @haze.setter + def haze(self, arg0: typing.SupportsFloat) -> None: ... + @property + def shadowclip(self) -> float: ... + @shadowclip.setter + def shadowclip(self, arg0: typing.SupportsFloat) -> None: ... + @property + def shadowscale(self) -> float: ... + @shadowscale.setter + def shadowscale(self, arg0: typing.SupportsFloat) -> None: ... + @property + def stiffness(self) -> float: ... + @stiffness.setter + def stiffness(self, arg0: typing.SupportsFloat) -> None: ... + @property + def stiffnessrot(self) -> float: ... + @stiffnessrot.setter + def stiffnessrot(self, arg0: typing.SupportsFloat) -> None: ... + @property + def torque(self) -> float: ... + @torque.setter + def torque(self, arg0: typing.SupportsFloat) -> None: ... + @property + def zfar(self) -> float: ... + @zfar.setter + def zfar(self, arg0: typing.SupportsFloat) -> None: ... + @property + def znear(self) -> float: ... + @znear.setter + def znear(self, arg0: typing.SupportsFloat) -> None: ... + + class Quality: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjVisual.Quality: ... + def __deepcopy__(self, arg0: dict) -> MjVisual.Quality: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __repr__(self) -> str: ... + @property + def numquads(self) -> int: ... + @numquads.setter + def numquads(self, arg0: typing.SupportsInt) -> None: ... + @property + def numslices(self) -> int: ... + @numslices.setter + def numslices(self, arg0: typing.SupportsInt) -> None: ... + @property + def numstacks(self) -> int: ... + @numstacks.setter + def numstacks(self, arg0: typing.SupportsInt) -> None: ... + @property + def offsamples(self) -> int: ... + @offsamples.setter + def offsamples(self, arg0: typing.SupportsInt) -> None: ... + @property + def shadowsize(self) -> int: ... + @shadowsize.setter + def shadowsize(self, arg0: typing.SupportsInt) -> None: ... + + class Rgba: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjVisual.Rgba: ... + def __deepcopy__(self, arg0: dict) -> MjVisual.Rgba: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __repr__(self) -> str: ... + @property + def actuator(self) -> numpy.typing.NDArray[numpy.float32]: ... + @actuator.setter + def actuator(self, arg1: typing.Any) -> None: ... + @property + def actuatornegative(self) -> numpy.typing.NDArray[numpy.float32]: ... + @actuatornegative.setter + def actuatornegative(self, arg1: typing.Any) -> None: ... + @property + def actuatorpositive(self) -> numpy.typing.NDArray[numpy.float32]: ... + @actuatorpositive.setter + def actuatorpositive(self, arg1: typing.Any) -> None: ... + @property + def bv(self) -> numpy.typing.NDArray[numpy.float32]: ... + @bv.setter + def bv(self, arg1: typing.Any) -> None: ... + @property + def bvactive(self) -> numpy.typing.NDArray[numpy.float32]: ... + @bvactive.setter + def bvactive(self, arg1: typing.Any) -> None: ... + @property + def camera(self) -> numpy.typing.NDArray[numpy.float32]: ... + @camera.setter + def camera(self, arg1: typing.Any) -> None: ... + @property + def com(self) -> numpy.typing.NDArray[numpy.float32]: ... + @com.setter + def com(self, arg1: typing.Any) -> None: ... + @property + def connect(self) -> numpy.typing.NDArray[numpy.float32]: ... + @connect.setter + def connect(self, arg1: typing.Any) -> None: ... + @property + def constraint(self) -> numpy.typing.NDArray[numpy.float32]: ... + @constraint.setter + def constraint(self, arg1: typing.Any) -> None: ... + @property + def contactforce(self) -> numpy.typing.NDArray[numpy.float32]: ... + @contactforce.setter + def contactforce(self, arg1: typing.Any) -> None: ... + @property + def contactfriction(self) -> numpy.typing.NDArray[numpy.float32]: ... + @contactfriction.setter + def contactfriction(self, arg1: typing.Any) -> None: ... + @property + def contactgap(self) -> numpy.typing.NDArray[numpy.float32]: ... + @contactgap.setter + def contactgap(self, arg1: typing.Any) -> None: ... + @property + def contactpoint(self) -> numpy.typing.NDArray[numpy.float32]: ... + @contactpoint.setter + def contactpoint(self, arg1: typing.Any) -> None: ... + @property + def contacttorque(self) -> numpy.typing.NDArray[numpy.float32]: ... + @contacttorque.setter + def contacttorque(self, arg1: typing.Any) -> None: ... + @property + def crankbroken(self) -> numpy.typing.NDArray[numpy.float32]: ... + @crankbroken.setter + def crankbroken(self, arg1: typing.Any) -> None: ... + @property + def fog(self) -> numpy.typing.NDArray[numpy.float32]: ... + @fog.setter + def fog(self, arg1: typing.Any) -> None: ... + @property + def force(self) -> numpy.typing.NDArray[numpy.float32]: ... + @force.setter + def force(self, arg1: typing.Any) -> None: ... + @property + def frustum(self) -> numpy.typing.NDArray[numpy.float32]: ... + @frustum.setter + def frustum(self, arg1: typing.Any) -> None: ... + @property + def haze(self) -> numpy.typing.NDArray[numpy.float32]: ... + @haze.setter + def haze(self, arg1: typing.Any) -> None: ... + @property + def inertia(self) -> numpy.typing.NDArray[numpy.float32]: ... + @inertia.setter + def inertia(self, arg1: typing.Any) -> None: ... + @property + def joint(self) -> numpy.typing.NDArray[numpy.float32]: ... + @joint.setter + def joint(self, arg1: typing.Any) -> None: ... + @property + def light(self) -> numpy.typing.NDArray[numpy.float32]: ... + @light.setter + def light(self, arg1: typing.Any) -> None: ... + @property + def rangefinder(self) -> numpy.typing.NDArray[numpy.float32]: ... + @rangefinder.setter + def rangefinder(self, arg1: typing.Any) -> None: ... + @property + def selectpoint(self) -> numpy.typing.NDArray[numpy.float32]: ... + @selectpoint.setter + def selectpoint(self, arg1: typing.Any) -> None: ... + @property + def slidercrank(self) -> numpy.typing.NDArray[numpy.float32]: ... + @slidercrank.setter + def slidercrank(self, arg1: typing.Any) -> None: ... + + class Scale: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjVisual.Scale: ... + def __deepcopy__(self, arg0: dict) -> MjVisual.Scale: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __repr__(self) -> str: ... + @property + def actuatorlength(self) -> float: ... + @actuatorlength.setter + def actuatorlength(self, arg0: typing.SupportsFloat) -> None: ... + @property + def actuatorwidth(self) -> float: ... + @actuatorwidth.setter + def actuatorwidth(self, arg0: typing.SupportsFloat) -> None: ... + @property + def camera(self) -> float: ... + @camera.setter + def camera(self, arg0: typing.SupportsFloat) -> None: ... + @property + def com(self) -> float: ... + @com.setter + def com(self, arg0: typing.SupportsFloat) -> None: ... + @property + def connect(self) -> float: ... + @connect.setter + def connect(self, arg0: typing.SupportsFloat) -> None: ... + @property + def constraint(self) -> float: ... + @constraint.setter + def constraint(self, arg0: typing.SupportsFloat) -> None: ... + @property + def contactheight(self) -> float: ... + @contactheight.setter + def contactheight(self, arg0: typing.SupportsFloat) -> None: ... + @property + def contactwidth(self) -> float: ... + @contactwidth.setter + def contactwidth(self, arg0: typing.SupportsFloat) -> None: ... + @property + def forcewidth(self) -> float: ... + @forcewidth.setter + def forcewidth(self, arg0: typing.SupportsFloat) -> None: ... + @property + def framelength(self) -> float: ... + @framelength.setter + def framelength(self, arg0: typing.SupportsFloat) -> None: ... + @property + def framewidth(self) -> float: ... + @framewidth.setter + def framewidth(self, arg0: typing.SupportsFloat) -> None: ... + @property + def frustum(self) -> float: ... + @frustum.setter + def frustum(self, arg0: typing.SupportsFloat) -> None: ... + @property + def jointlength(self) -> float: ... + @jointlength.setter + def jointlength(self, arg0: typing.SupportsFloat) -> None: ... + @property + def jointwidth(self) -> float: ... + @jointwidth.setter + def jointwidth(self, arg0: typing.SupportsFloat) -> None: ... + @property + def light(self) -> float: ... + @light.setter + def light(self, arg0: typing.SupportsFloat) -> None: ... + @property + def selectpoint(self) -> float: ... + @selectpoint.setter + def selectpoint(self, arg0: typing.SupportsFloat) -> None: ... + @property + def slidercrank(self) -> float: ... + @slidercrank.setter + def slidercrank(self, arg0: typing.SupportsFloat) -> None: ... + + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjVisual: ... + def __deepcopy__(self, arg0: dict) -> MjVisual: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __repr__(self) -> str: ... + @property + def global_(self) -> MjVisual.Global: ... + @property + def headlight(self) -> MjVisual.Headlight: ... + @property + def map(self) -> MjVisual.Map: ... + @property + def quality(self) -> MjVisual.Quality: ... + @property + def rgba(self) -> MjVisual.Rgba: ... + @property + def scale(self) -> MjVisual.Scale: ... + +class MjWarningStat: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjWarningStat: ... + def __deepcopy__(self, arg0: dict) -> MjWarningStat: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def lastinfo(self) -> int: ... + @lastinfo.setter + def lastinfo(self, arg1: typing.SupportsInt) -> None: ... + @property + def number(self) -> int: ... + @number.setter + def number(self, arg1: typing.SupportsInt) -> None: ... + +class MjvCamera: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjvCamera: ... + def __deepcopy__(self, arg0: dict) -> MjvCamera: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def azimuth(self) -> float: ... + @azimuth.setter + def azimuth(self, arg1: typing.SupportsFloat) -> None: ... + @property + def distance(self) -> float: ... + @distance.setter + def distance(self, arg1: typing.SupportsFloat) -> None: ... + @property + def elevation(self) -> float: ... + @elevation.setter + def elevation(self, arg1: typing.SupportsFloat) -> None: ... + @property + def fixedcamid(self) -> int: ... + @fixedcamid.setter + def fixedcamid(self, arg1: typing.SupportsInt) -> None: ... + @property + def lookat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @lookat.setter + def lookat(self, arg1: typing.Any) -> None: ... + @property + def orthographic(self) -> int: ... + @orthographic.setter + def orthographic(self, arg1: typing.SupportsInt) -> None: ... + @property + def trackbodyid(self) -> int: ... + @trackbodyid.setter + def trackbodyid(self, arg1: typing.SupportsInt) -> None: ... + @property + def type(self) -> int: ... + @type.setter + def type(self, arg1: typing.SupportsInt) -> None: ... + +class MjvFigure: + minwidth: str + title: str + xformat: str + xlabel: str + yformat: str + def __copy__(self) -> MjvFigure: ... + def __deepcopy__(self, arg0: dict) -> MjvFigure: ... + def __init__(self) -> None: ... + @property + def figurergba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @figurergba.setter + def figurergba(self, arg1: typing.Any) -> None: ... + @property + def flg_barplot(self) -> int: ... + @flg_barplot.setter + def flg_barplot(self, arg1: typing.SupportsInt) -> None: ... + @property + def flg_extend(self) -> int: ... + @flg_extend.setter + def flg_extend(self, arg1: typing.SupportsInt) -> None: ... + @property + def flg_legend(self) -> int: ... + @flg_legend.setter + def flg_legend(self, arg1: typing.SupportsInt) -> None: ... + @property + def flg_selection(self) -> int: ... + @flg_selection.setter + def flg_selection(self, arg1: typing.SupportsInt) -> None: ... + @property + def flg_symmetric(self) -> int: ... + @flg_symmetric.setter + def flg_symmetric(self, arg1: typing.SupportsInt) -> None: ... + @property + def flg_ticklabel(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flg_ticklabel.setter + def flg_ticklabel(self, arg1: typing.Any) -> None: ... + @property + def gridrgb(self) -> numpy.typing.NDArray[numpy.float32]: ... + @gridrgb.setter + def gridrgb(self, arg1: typing.Any) -> None: ... + @property + def gridsize(self) -> numpy.typing.NDArray[numpy.int32]: ... + @gridsize.setter + def gridsize(self, arg1: typing.Any) -> None: ... + @property + def gridwidth(self) -> float: ... + @gridwidth.setter + def gridwidth(self, arg1: typing.SupportsFloat) -> None: ... + @property + def highlight(self) -> numpy.typing.NDArray[numpy.int32]: ... + @highlight.setter + def highlight(self, arg1: typing.Any) -> None: ... + @property + def highlightid(self) -> int: ... + @highlightid.setter + def highlightid(self, arg1: typing.SupportsInt) -> None: ... + @property + def legendoffset(self) -> int: ... + @legendoffset.setter + def legendoffset(self, arg1: typing.SupportsInt) -> None: ... + @property + def legendrgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @legendrgba.setter + def legendrgba(self, arg1: typing.Any) -> None: ... + @property + def linedata(self) -> numpy.typing.NDArray[numpy.float32]: ... + @linedata.setter + def linedata(self, arg1: typing.Any) -> None: ... + @property + def linename(self) -> numpy.ndarray: ... + @property + def linepnt(self) -> numpy.typing.NDArray[numpy.int32]: ... + @linepnt.setter + def linepnt(self, arg1: typing.Any) -> None: ... + @property + def linergb(self) -> numpy.typing.NDArray[numpy.float32]: ... + @linergb.setter + def linergb(self, arg1: typing.Any) -> None: ... + @property + def linewidth(self) -> float: ... + @linewidth.setter + def linewidth(self, arg1: typing.SupportsFloat) -> None: ... + @property + def panergba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @panergba.setter + def panergba(self, arg1: typing.Any) -> None: ... + @property + def range(self) -> numpy.typing.NDArray[numpy.float32]: ... + @range.setter + def range(self, arg1: typing.Any) -> None: ... + @property + def selection(self) -> float: ... + @selection.setter + def selection(self, arg1: typing.SupportsFloat) -> None: ... + @property + def subplot(self) -> int: ... + @subplot.setter + def subplot(self, arg1: typing.SupportsInt) -> None: ... + @property + def textrgb(self) -> numpy.typing.NDArray[numpy.float32]: ... + @textrgb.setter + def textrgb(self, arg1: typing.Any) -> None: ... + @property + def xaxisdata(self) -> numpy.typing.NDArray[numpy.float32]: ... + @xaxisdata.setter + def xaxisdata(self, arg1: typing.Any) -> None: ... + @property + def xaxispixel(self) -> numpy.typing.NDArray[numpy.int32]: ... + @xaxispixel.setter + def xaxispixel(self, arg1: typing.Any) -> None: ... + @property + def yaxisdata(self) -> numpy.typing.NDArray[numpy.float32]: ... + @yaxisdata.setter + def yaxisdata(self, arg1: typing.Any) -> None: ... + @property + def yaxispixel(self) -> numpy.typing.NDArray[numpy.int32]: ... + @yaxispixel.setter + def yaxispixel(self, arg1: typing.Any) -> None: ... + +class MjvGLCamera: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjvGLCamera: ... + def __deepcopy__(self, arg0: dict) -> MjvGLCamera: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def forward(self) -> numpy.typing.NDArray[numpy.float32]: ... + @forward.setter + def forward(self, arg1: typing.Any) -> None: ... + @property + def frustum_bottom(self) -> float: ... + @frustum_bottom.setter + def frustum_bottom(self, arg1: typing.SupportsFloat) -> None: ... + @property + def frustum_center(self) -> float: ... + @frustum_center.setter + def frustum_center(self, arg1: typing.SupportsFloat) -> None: ... + @property + def frustum_far(self) -> float: ... + @frustum_far.setter + def frustum_far(self, arg1: typing.SupportsFloat) -> None: ... + @property + def frustum_near(self) -> float: ... + @frustum_near.setter + def frustum_near(self, arg1: typing.SupportsFloat) -> None: ... + @property + def frustum_top(self) -> float: ... + @frustum_top.setter + def frustum_top(self, arg1: typing.SupportsFloat) -> None: ... + @property + def frustum_width(self) -> float: ... + @frustum_width.setter + def frustum_width(self, arg1: typing.SupportsFloat) -> None: ... + @property + def orthographic(self) -> int: ... + @orthographic.setter + def orthographic(self, arg1: typing.SupportsInt) -> None: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float32]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def up(self) -> numpy.typing.NDArray[numpy.float32]: ... + @up.setter + def up(self, arg1: typing.Any) -> None: ... + +class MjvGeom: + __hash__: typing.ClassVar[None] = None + label: str + def __copy__(self) -> MjvGeom: ... + def __deepcopy__(self, arg0: dict) -> MjvGeom: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def camdist(self) -> float: ... + @camdist.setter + def camdist(self, arg1: typing.SupportsFloat) -> None: ... + @property + def category(self) -> int: ... + @category.setter + def category(self, arg1: typing.SupportsInt) -> None: ... + @property + def dataid(self) -> int: ... + @dataid.setter + def dataid(self, arg1: typing.SupportsInt) -> None: ... + @property + def emission(self) -> float: ... + @emission.setter + def emission(self, arg1: typing.SupportsFloat) -> None: ... + @property + def mat(self) -> numpy.typing.NDArray[numpy.float32]: ... + @mat.setter + def mat(self, arg1: typing.Any) -> None: ... + @property + def matid(self) -> int: ... + @matid.setter + def matid(self, arg1: typing.SupportsInt) -> None: ... + @property + def modelrbound(self) -> float: ... + @modelrbound.setter + def modelrbound(self, arg1: typing.SupportsFloat) -> None: ... + @property + def objid(self) -> int: ... + @objid.setter + def objid(self, arg1: typing.SupportsInt) -> None: ... + @property + def objtype(self) -> int: ... + @objtype.setter + def objtype(self, arg1: typing.SupportsInt) -> None: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float32]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def reflectance(self) -> float: ... + @reflectance.setter + def reflectance(self, arg1: typing.SupportsFloat) -> None: ... + @property + def rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @rgba.setter + def rgba(self, arg1: typing.Any) -> None: ... + @property + def segid(self) -> int: ... + @segid.setter + def segid(self, arg1: typing.SupportsInt) -> None: ... + @property + def shininess(self) -> float: ... + @shininess.setter + def shininess(self, arg1: typing.SupportsFloat) -> None: ... + @property + def size(self) -> numpy.typing.NDArray[numpy.float32]: ... + @size.setter + def size(self, arg1: typing.Any) -> None: ... + @property + def specular(self) -> float: ... + @specular.setter + def specular(self, arg1: typing.SupportsFloat) -> None: ... + @property + def texcoord(self) -> int: ... + @texcoord.setter + def texcoord(self, arg1: typing.SupportsInt) -> None: ... + @property + def transparent(self) -> int: ... + @transparent.setter + def transparent(self, arg1: typing.SupportsInt) -> None: ... + @property + def type(self) -> int: ... + @type.setter + def type(self, arg1: typing.SupportsInt) -> None: ... + +class MjvLight: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjvLight: ... + def __deepcopy__(self, arg0: dict) -> MjvLight: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def ambient(self) -> numpy.typing.NDArray[numpy.float32]: ... + @ambient.setter + def ambient(self, arg1: typing.Any) -> None: ... + @property + def attenuation(self) -> numpy.typing.NDArray[numpy.float32]: ... + @attenuation.setter + def attenuation(self, arg1: typing.Any) -> None: ... + @property + def bulbradius(self) -> float: ... + @bulbradius.setter + def bulbradius(self, arg1: typing.SupportsFloat) -> None: ... + @property + def castshadow(self) -> int: ... + @castshadow.setter + def castshadow(self, arg1: typing.SupportsInt) -> None: ... + @property + def cutoff(self) -> float: ... + @cutoff.setter + def cutoff(self, arg1: typing.SupportsFloat) -> None: ... + @property + def diffuse(self) -> numpy.typing.NDArray[numpy.float32]: ... + @diffuse.setter + def diffuse(self, arg1: typing.Any) -> None: ... + @property + def dir(self) -> numpy.typing.NDArray[numpy.float32]: ... + @dir.setter + def dir(self, arg1: typing.Any) -> None: ... + @property + def exponent(self) -> float: ... + @exponent.setter + def exponent(self, arg1: typing.SupportsFloat) -> None: ... + @property + def headlight(self) -> int: ... + @headlight.setter + def headlight(self, arg1: typing.SupportsInt) -> None: ... + @property + def intensity(self) -> float: ... + @intensity.setter + def intensity(self, arg1: typing.SupportsFloat) -> None: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float32]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def range(self) -> float: ... + @range.setter + def range(self, arg1: typing.SupportsFloat) -> None: ... + @property + def specular(self) -> numpy.typing.NDArray[numpy.float32]: ... + @specular.setter + def specular(self, arg1: typing.Any) -> None: ... + @property + def texid(self) -> int: ... + @texid.setter + def texid(self, arg1: typing.SupportsInt) -> None: ... + @property + def type(self) -> int: ... + @type.setter + def type(self, arg1: typing.SupportsInt) -> None: ... + +class MjvOption: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjvOption: ... + def __deepcopy__(self, arg0: dict) -> MjvOption: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def actuatorgroup(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @actuatorgroup.setter + def actuatorgroup(self, arg1: typing.Any) -> None: ... + @property + def bvh_depth(self) -> int: ... + @bvh_depth.setter + def bvh_depth(self, arg1: typing.SupportsInt) -> None: ... + @property + def flags(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flags.setter + def flags(self, arg1: typing.Any) -> None: ... + @property + def flex_layer(self) -> int: ... + @flex_layer.setter + def flex_layer(self, arg1: typing.SupportsInt) -> None: ... + @property + def flexgroup(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flexgroup.setter + def flexgroup(self, arg1: typing.Any) -> None: ... + @property + def frame(self) -> int: ... + @frame.setter + def frame(self, arg1: typing.SupportsInt) -> None: ... + @property + def geomgroup(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @geomgroup.setter + def geomgroup(self, arg1: typing.Any) -> None: ... + @property + def jointgroup(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @jointgroup.setter + def jointgroup(self, arg1: typing.Any) -> None: ... + @property + def label(self) -> int: ... + @label.setter + def label(self, arg1: typing.SupportsInt) -> None: ... + @property + def sitegroup(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @sitegroup.setter + def sitegroup(self, arg1: typing.Any) -> None: ... + @property + def skingroup(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @skingroup.setter + def skingroup(self, arg1: typing.Any) -> None: ... + @property + def tendongroup(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @tendongroup.setter + def tendongroup(self, arg1: typing.Any) -> None: ... + +class MjvPerturb: + __hash__: typing.ClassVar[None] = None + def __copy__(self) -> MjvPerturb: ... + def __deepcopy__(self, arg0: dict) -> MjvPerturb: ... + def __eq__(self, arg0: typing.Any) -> bool: ... + def __init__(self) -> None: ... + def __repr__(self) -> str: ... + @property + def active(self) -> int: ... + @active.setter + def active(self, arg1: typing.SupportsInt) -> None: ... + @property + def active2(self) -> int: ... + @active2.setter + def active2(self, arg1: typing.SupportsInt) -> None: ... + @property + def flexselect(self) -> int: ... + @flexselect.setter + def flexselect(self, arg1: typing.SupportsInt) -> None: ... + @property + def localmass(self) -> float: ... + @localmass.setter + def localmass(self, arg1: typing.SupportsFloat) -> None: ... + @property + def localpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @localpos.setter + def localpos(self, arg1: typing.Any) -> None: ... + @property + def refpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @refpos.setter + def refpos(self, arg1: typing.Any) -> None: ... + @property + def refquat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @refquat.setter + def refquat(self, arg1: typing.Any) -> None: ... + @property + def refselpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @refselpos.setter + def refselpos(self, arg1: typing.Any) -> None: ... + @property + def scale(self) -> float: ... + @scale.setter + def scale(self, arg1: typing.SupportsFloat) -> None: ... + @property + def select(self) -> int: ... + @select.setter + def select(self, arg1: typing.SupportsInt) -> None: ... + @property + def skinselect(self) -> int: ... + @skinselect.setter + def skinselect(self, arg1: typing.SupportsInt) -> None: ... + +class MjvScene: + def __copy__(self) -> MjvScene: ... + def __deepcopy__(self, arg0: dict) -> MjvScene: ... + @typing.overload + def __init__(self) -> None: ... + @typing.overload + def __init__(self, model: MjModel, maxgeom: typing.SupportsInt) -> None: ... + @property + def camera(self) -> tuple: ... + @property + def enabletransform(self) -> int: ... + @enabletransform.setter + def enabletransform(self, arg1: typing.SupportsInt) -> None: ... + @property + def flags(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @flags.setter + def flags(self, arg1: typing.Any) -> None: ... + @property + def flexedge(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexedge.setter + def flexedge(self, arg1: typing.Any) -> None: ... + @property + def flexedgeadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexedgeadr.setter + def flexedgeadr(self, arg1: typing.Any) -> None: ... + @property + def flexedgenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexedgenum.setter + def flexedgenum(self, arg1: typing.Any) -> None: ... + @property + def flexedgeopt(self) -> int: ... + @flexedgeopt.setter + def flexedgeopt(self, arg1: typing.SupportsInt) -> None: ... + @property + def flexface(self) -> numpy.typing.NDArray[numpy.float32]: ... + @flexface.setter + def flexface(self, arg1: typing.Any) -> None: ... + @property + def flexfaceadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexfaceadr.setter + def flexfaceadr(self, arg1: typing.Any) -> None: ... + @property + def flexfacenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexfacenum.setter + def flexfacenum(self, arg1: typing.Any) -> None: ... + @property + def flexfaceopt(self) -> int: ... + @flexfaceopt.setter + def flexfaceopt(self, arg1: typing.SupportsInt) -> None: ... + @property + def flexfaceused(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexfaceused.setter + def flexfaceused(self, arg1: typing.Any) -> None: ... + @property + def flexnormal(self) -> numpy.typing.NDArray[numpy.float32]: ... + @flexnormal.setter + def flexnormal(self, arg1: typing.Any) -> None: ... + @property + def flexskinopt(self) -> int: ... + @flexskinopt.setter + def flexskinopt(self, arg1: typing.SupportsInt) -> None: ... + @property + def flextexcoord(self) -> numpy.typing.NDArray[numpy.float32]: ... + @flextexcoord.setter + def flextexcoord(self, arg1: typing.Any) -> None: ... + @property + def flexvert(self) -> numpy.typing.NDArray[numpy.float32]: ... + @flexvert.setter + def flexvert(self, arg1: typing.Any) -> None: ... + @property + def flexvertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexvertadr.setter + def flexvertadr(self, arg1: typing.Any) -> None: ... + @property + def flexvertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @flexvertnum.setter + def flexvertnum(self, arg1: typing.Any) -> None: ... + @property + def flexvertopt(self) -> int: ... + @flexvertopt.setter + def flexvertopt(self, arg1: typing.SupportsInt) -> None: ... + @property + def framergb(self) -> numpy.typing.NDArray[numpy.float32]: ... + @framergb.setter + def framergb(self, arg1: typing.Any) -> None: ... + @property + def framewidth(self) -> int: ... + @framewidth.setter + def framewidth(self, arg1: typing.SupportsInt) -> None: ... + @property + def geomorder(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geomorder.setter + def geomorder(self, arg1: typing.Any) -> None: ... + @property + def geoms(self) -> tuple: ... + @property + def lights(self) -> tuple: ... + @property + def maxgeom(self) -> int: ... + @maxgeom.setter + def maxgeom(self, arg1: typing.SupportsInt) -> None: ... + @property + def nflex(self) -> int: ... + @nflex.setter + def nflex(self, arg1: typing.SupportsInt) -> None: ... + @property + def ngeom(self) -> int: ... + @ngeom.setter + def ngeom(self, arg1: typing.SupportsInt) -> None: ... + @property + def nlight(self) -> int: ... + @nlight.setter + def nlight(self, arg1: typing.SupportsInt) -> None: ... + @property + def nskin(self) -> int: ... + @nskin.setter + def nskin(self, arg1: typing.SupportsInt) -> None: ... + @property + def rotate(self) -> numpy.typing.NDArray[numpy.float32]: ... + @rotate.setter + def rotate(self, arg1: typing.Any) -> None: ... + @property + def scale(self) -> float: ... + @scale.setter + def scale(self, arg1: typing.SupportsFloat) -> None: ... + @property + def skinfacenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skinfacenum.setter + def skinfacenum(self, arg1: typing.Any) -> None: ... + @property + def skinnormal(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skinnormal.setter + def skinnormal(self, arg1: typing.Any) -> None: ... + @property + def skinvert(self) -> numpy.typing.NDArray[numpy.float32]: ... + @skinvert.setter + def skinvert(self, arg1: typing.Any) -> None: ... + @property + def skinvertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skinvertadr.setter + def skinvertadr(self, arg1: typing.Any) -> None: ... + @property + def skinvertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @skinvertnum.setter + def skinvertnum(self, arg1: typing.Any) -> None: ... + @property + def stereo(self) -> int: ... + @stereo.setter + def stereo(self, arg1: typing.SupportsInt) -> None: ... + @property + def translate(self) -> numpy.typing.NDArray[numpy.float32]: ... + @translate.setter + def translate(self, arg1: typing.Any) -> None: ... + +class _MjContactList: + __hash__: typing.ClassVar[None] = None + def __eq__(self, arg0: typing.Any) -> bool: ... + @typing.overload + def __getitem__(self, arg0: typing.SupportsInt) -> MjContact: ... + @typing.overload + def __getitem__(self, arg0: slice) -> _MjContactList: ... + def __len__(self) -> int: ... + def __repr__(self) -> str: ... + @property + def H(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def dim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def dist(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def efc_address(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def elem(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def exclude(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def flex(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def frame(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def geom(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def geom1(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def geom2(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def includemargin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def mu(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def solreffriction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def vert(self) -> numpy.typing.NDArray[numpy.int32]: ... + +class _MjDataActuatorViews: + def __repr__(self) -> str: ... + @property + def ctrl(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ctrl.setter + def ctrl(self, arg1: typing.Any) -> None: ... + @property + def force(self) -> numpy.typing.NDArray[numpy.float64]: ... + @force.setter + def force(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def length(self) -> numpy.typing.NDArray[numpy.float64]: ... + @length.setter + def length(self, arg1: typing.Any) -> None: ... + @property + def moment(self) -> numpy.typing.NDArray[numpy.float64]: ... + @moment.setter + def moment(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def velocity(self) -> numpy.typing.NDArray[numpy.float64]: ... + @velocity.setter + def velocity(self, arg1: typing.Any) -> None: ... + +class _MjDataBodyViews: + def __repr__(self) -> str: ... + @property + def cacc(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cacc.setter + def cacc(self, arg1: typing.Any) -> None: ... + @property + def cfrc_ext(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cfrc_ext.setter + def cfrc_ext(self, arg1: typing.Any) -> None: ... + @property + def cfrc_int(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cfrc_int.setter + def cfrc_int(self, arg1: typing.Any) -> None: ... + @property + def cinert(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cinert.setter + def cinert(self, arg1: typing.Any) -> None: ... + @property + def crb(self) -> numpy.typing.NDArray[numpy.float64]: ... + @crb.setter + def crb(self, arg1: typing.Any) -> None: ... + @property + def cvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cvel.setter + def cvel(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def subtree_angmom(self) -> numpy.typing.NDArray[numpy.float64]: ... + @subtree_angmom.setter + def subtree_angmom(self, arg1: typing.Any) -> None: ... + @property + def subtree_com(self) -> numpy.typing.NDArray[numpy.float64]: ... + @subtree_com.setter + def subtree_com(self, arg1: typing.Any) -> None: ... + @property + def subtree_linvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @subtree_linvel.setter + def subtree_linvel(self, arg1: typing.Any) -> None: ... + @property + def xfrc_applied(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xfrc_applied.setter + def xfrc_applied(self, arg1: typing.Any) -> None: ... + @property + def ximat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ximat.setter + def ximat(self, arg1: typing.Any) -> None: ... + @property + def xipos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xipos.setter + def xipos(self, arg1: typing.Any) -> None: ... + @property + def xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xmat.setter + def xmat(self, arg1: typing.Any) -> None: ... + @property + def xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xpos.setter + def xpos(self, arg1: typing.Any) -> None: ... + @property + def xquat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xquat.setter + def xquat(self, arg1: typing.Any) -> None: ... + +class _MjDataCameraViews: + def __repr__(self) -> str: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xmat.setter + def xmat(self, arg1: typing.Any) -> None: ... + @property + def xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xpos.setter + def xpos(self, arg1: typing.Any) -> None: ... + +class _MjDataGeomViews: + def __repr__(self) -> str: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xmat.setter + def xmat(self, arg1: typing.Any) -> None: ... + @property + def xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xpos.setter + def xpos(self, arg1: typing.Any) -> None: ... + +class _MjDataJointViews: + def __repr__(self) -> str: ... + @property + def cdof(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cdof.setter + def cdof(self, arg1: typing.Any) -> None: ... + @property + def cdof_dot(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cdof_dot.setter + def cdof_dot(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def qLDiagInv(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qLDiagInv.setter + def qLDiagInv(self, arg1: typing.Any) -> None: ... + @property + def qacc(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qacc.setter + def qacc(self, arg1: typing.Any) -> None: ... + @property + def qacc_smooth(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qacc_smooth.setter + def qacc_smooth(self, arg1: typing.Any) -> None: ... + @property + def qacc_warmstart(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qacc_warmstart.setter + def qacc_warmstart(self, arg1: typing.Any) -> None: ... + @property + def qfrc_actuator(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_actuator.setter + def qfrc_actuator(self, arg1: typing.Any) -> None: ... + @property + def qfrc_applied(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_applied.setter + def qfrc_applied(self, arg1: typing.Any) -> None: ... + @property + def qfrc_bias(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_bias.setter + def qfrc_bias(self, arg1: typing.Any) -> None: ... + @property + def qfrc_constraint(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_constraint.setter + def qfrc_constraint(self, arg1: typing.Any) -> None: ... + @property + def qfrc_inverse(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_inverse.setter + def qfrc_inverse(self, arg1: typing.Any) -> None: ... + @property + def qfrc_passive(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_passive.setter + def qfrc_passive(self, arg1: typing.Any) -> None: ... + @property + def qfrc_smooth(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qfrc_smooth.setter + def qfrc_smooth(self, arg1: typing.Any) -> None: ... + @property + def qpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qpos.setter + def qpos(self, arg1: typing.Any) -> None: ... + @property + def qvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qvel.setter + def qvel(self, arg1: typing.Any) -> None: ... + @property + def xanchor(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xanchor.setter + def xanchor(self, arg1: typing.Any) -> None: ... + @property + def xaxis(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xaxis.setter + def xaxis(self, arg1: typing.Any) -> None: ... + +class _MjDataLightViews: + def __repr__(self) -> str: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def xdir(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xdir.setter + def xdir(self, arg1: typing.Any) -> None: ... + @property + def xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xpos.setter + def xpos(self, arg1: typing.Any) -> None: ... + +class _MjDataSensorViews: + def __repr__(self) -> str: ... + @property + def data(self) -> numpy.typing.NDArray[numpy.float64]: ... + @data.setter + def data(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + +class _MjDataSiteViews: + def __repr__(self) -> str: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def xmat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xmat.setter + def xmat(self, arg1: typing.Any) -> None: ... + @property + def xpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @xpos.setter + def xpos(self, arg1: typing.Any) -> None: ... + +class _MjDataTendonViews: + def __repr__(self) -> str: ... + @property + def J(self) -> numpy.typing.NDArray[numpy.float64]: ... + @J.setter + def J(self, arg1: typing.Any) -> None: ... + @property + def J_colind(self) -> numpy.typing.NDArray[numpy.int32]: ... + @J_colind.setter + def J_colind(self, arg1: typing.Any) -> None: ... + @property + def J_rowadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @J_rowadr.setter + def J_rowadr(self, arg1: typing.Any) -> None: ... + @property + def J_rownnz(self) -> numpy.typing.NDArray[numpy.int32]: ... + @J_rownnz.setter + def J_rownnz(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def length(self) -> numpy.typing.NDArray[numpy.float64]: ... + @length.setter + def length(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def velocity(self) -> numpy.typing.NDArray[numpy.float64]: ... + @velocity.setter + def velocity(self, arg1: typing.Any) -> None: ... + @property + def wrapadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @wrapadr.setter + def wrapadr(self, arg1: typing.Any) -> None: ... + @property + def wrapnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @wrapnum.setter + def wrapnum(self, arg1: typing.Any) -> None: ... + +class _MjModelActuatorViews: + def __repr__(self) -> str: ... + @property + def acc0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @acc0.setter + def acc0(self, arg1: typing.Any) -> None: ... + @property + def actadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actadr.setter + def actadr(self, arg1: typing.Any) -> None: ... + @property + def actlimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @actlimited.setter + def actlimited(self, arg1: typing.Any) -> None: ... + @property + def actnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @actnum.setter + def actnum(self, arg1: typing.Any) -> None: ... + @property + def actrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @actrange.setter + def actrange(self, arg1: typing.Any) -> None: ... + @property + def biasprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @biasprm.setter + def biasprm(self, arg1: typing.Any) -> None: ... + @property + def biastype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @biastype.setter + def biastype(self, arg1: typing.Any) -> None: ... + @property + def cranklength(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cranklength.setter + def cranklength(self, arg1: typing.Any) -> None: ... + @property + def ctrllimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @ctrllimited.setter + def ctrllimited(self, arg1: typing.Any) -> None: ... + @property + def ctrlrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ctrlrange.setter + def ctrlrange(self, arg1: typing.Any) -> None: ... + @property + def dynprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dynprm.setter + def dynprm(self, arg1: typing.Any) -> None: ... + @property + def dyntype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dyntype.setter + def dyntype(self, arg1: typing.Any) -> None: ... + @property + def forcelimited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @forcelimited.setter + def forcelimited(self, arg1: typing.Any) -> None: ... + @property + def forcerange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @forcerange.setter + def forcerange(self, arg1: typing.Any) -> None: ... + @property + def gainprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @gainprm.setter + def gainprm(self, arg1: typing.Any) -> None: ... + @property + def gaintype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @gaintype.setter + def gaintype(self, arg1: typing.Any) -> None: ... + @property + def gear(self) -> numpy.typing.NDArray[numpy.float64]: ... + @gear.setter + def gear(self, arg1: typing.Any) -> None: ... + @property + def group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @group.setter + def group(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def length0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @length0.setter + def length0(self, arg1: typing.Any) -> None: ... + @property + def lengthrange(self) -> numpy.typing.NDArray[numpy.float64]: ... + @lengthrange.setter + def lengthrange(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def trnid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @trnid.setter + def trnid(self, arg1: typing.Any) -> None: ... + @property + def trntype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @trntype.setter + def trntype(self, arg1: typing.Any) -> None: ... + @property + def user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @user.setter + def user(self, arg1: typing.Any) -> None: ... + +class _MjModelBodyViews: + def __repr__(self) -> str: ... + @property + def dofadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dofadr.setter + def dofadr(self, arg1: typing.Any) -> None: ... + @property + def dofnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dofnum.setter + def dofnum(self, arg1: typing.Any) -> None: ... + @property + def geomadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geomadr.setter + def geomadr(self, arg1: typing.Any) -> None: ... + @property + def geomnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geomnum.setter + def geomnum(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def inertia(self) -> numpy.typing.NDArray[numpy.float64]: ... + @inertia.setter + def inertia(self, arg1: typing.Any) -> None: ... + @property + def invweight0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @invweight0.setter + def invweight0(self, arg1: typing.Any) -> None: ... + @property + def ipos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ipos.setter + def ipos(self, arg1: typing.Any) -> None: ... + @property + def iquat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @iquat.setter + def iquat(self, arg1: typing.Any) -> None: ... + @property + def jntadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jntadr.setter + def jntadr(self, arg1: typing.Any) -> None: ... + @property + def jntnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jntnum.setter + def jntnum(self, arg1: typing.Any) -> None: ... + @property + def mass(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mass.setter + def mass(self, arg1: typing.Any) -> None: ... + @property + def mocapid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mocapid.setter + def mocapid(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def parentid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @parentid.setter + def parentid(self, arg1: typing.Any) -> None: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @quat.setter + def quat(self, arg1: typing.Any) -> None: ... + @property + def rootid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @rootid.setter + def rootid(self, arg1: typing.Any) -> None: ... + @property + def sameframe(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @sameframe.setter + def sameframe(self, arg1: typing.Any) -> None: ... + @property + def simple(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @simple.setter + def simple(self, arg1: typing.Any) -> None: ... + @property + def subtreemass(self) -> numpy.typing.NDArray[numpy.float64]: ... + @subtreemass.setter + def subtreemass(self, arg1: typing.Any) -> None: ... + @property + def user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @user.setter + def user(self, arg1: typing.Any) -> None: ... + @property + def weldid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @weldid.setter + def weldid(self, arg1: typing.Any) -> None: ... + +class _MjModelCameraViews: + def __repr__(self) -> str: ... + @property + def bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bodyid.setter + def bodyid(self, arg1: typing.Any) -> None: ... + @property + def fovy(self) -> numpy.typing.NDArray[numpy.float64]: ... + @fovy.setter + def fovy(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def ipd(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ipd.setter + def ipd(self, arg1: typing.Any) -> None: ... + @property + def mat0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mat0.setter + def mat0(self, arg1: typing.Any) -> None: ... + @property + def mode(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mode.setter + def mode(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def pos0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos0.setter + def pos0(self, arg1: typing.Any) -> None: ... + @property + def poscom0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @poscom0.setter + def poscom0(self, arg1: typing.Any) -> None: ... + @property + def quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @quat.setter + def quat(self, arg1: typing.Any) -> None: ... + @property + def targetbodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @targetbodyid.setter + def targetbodyid(self, arg1: typing.Any) -> None: ... + @property + def user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @user.setter + def user(self, arg1: typing.Any) -> None: ... + +class _MjModelEqualityViews: + def __repr__(self) -> str: ... + @property + def active0(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @active0.setter + def active0(self, arg1: typing.Any) -> None: ... + @property + def data(self) -> numpy.typing.NDArray[numpy.float64]: ... + @data.setter + def data(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def obj1id(self) -> numpy.typing.NDArray[numpy.int32]: ... + @obj1id.setter + def obj1id(self, arg1: typing.Any) -> None: ... + @property + def obj2id(self) -> numpy.typing.NDArray[numpy.int32]: ... + @obj2id.setter + def obj2id(self, arg1: typing.Any) -> None: ... + @property + def solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solimp.setter + def solimp(self, arg1: typing.Any) -> None: ... + @property + def solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solref.setter + def solref(self, arg1: typing.Any) -> None: ... + @property + def type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @type.setter + def type(self, arg1: typing.Any) -> None: ... + +class _MjModelExcludeViews: + def __repr__(self) -> str: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def signature(self) -> numpy.typing.NDArray[numpy.int32]: ... + @signature.setter + def signature(self, arg1: typing.Any) -> None: ... + +class _MjModelGeomViews: + def __repr__(self) -> str: ... + @property + def bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bodyid.setter + def bodyid(self, arg1: typing.Any) -> None: ... + @property + def conaffinity(self) -> numpy.typing.NDArray[numpy.int32]: ... + @conaffinity.setter + def conaffinity(self, arg1: typing.Any) -> None: ... + @property + def condim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @condim.setter + def condim(self, arg1: typing.Any) -> None: ... + @property + def contype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @contype.setter + def contype(self, arg1: typing.Any) -> None: ... + @property + def dataid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dataid.setter + def dataid(self, arg1: typing.Any) -> None: ... + @property + def friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @friction.setter + def friction(self, arg1: typing.Any) -> None: ... + @property + def gap(self) -> numpy.typing.NDArray[numpy.float64]: ... + @gap.setter + def gap(self, arg1: typing.Any) -> None: ... + @property + def group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @group.setter + def group(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @margin.setter + def margin(self, arg1: typing.Any) -> None: ... + @property + def matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @matid.setter + def matid(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def priority(self) -> numpy.typing.NDArray[numpy.int32]: ... + @priority.setter + def priority(self, arg1: typing.Any) -> None: ... + @property + def quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @quat.setter + def quat(self, arg1: typing.Any) -> None: ... + @property + def rbound(self) -> numpy.typing.NDArray[numpy.float64]: ... + @rbound.setter + def rbound(self, arg1: typing.Any) -> None: ... + @property + def rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @rgba.setter + def rgba(self, arg1: typing.Any) -> None: ... + @property + def sameframe(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @sameframe.setter + def sameframe(self, arg1: typing.Any) -> None: ... + @property + def size(self) -> numpy.typing.NDArray[numpy.float64]: ... + @size.setter + def size(self, arg1: typing.Any) -> None: ... + @property + def solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solimp.setter + def solimp(self, arg1: typing.Any) -> None: ... + @property + def solmix(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solmix.setter + def solmix(self, arg1: typing.Any) -> None: ... + @property + def solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solref.setter + def solref(self, arg1: typing.Any) -> None: ... + @property + def type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @type.setter + def type(self, arg1: typing.Any) -> None: ... + @property + def user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @user.setter + def user(self, arg1: typing.Any) -> None: ... + +class _MjModelHfieldViews: + def __repr__(self) -> str: ... + @property + def adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @adr.setter + def adr(self, arg1: typing.Any) -> None: ... + @property + def data(self) -> numpy.typing.NDArray[numpy.float32]: ... + @data.setter + def data(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def ncol(self) -> numpy.typing.NDArray[numpy.int32]: ... + @ncol.setter + def ncol(self, arg1: typing.Any) -> None: ... + @property + def nrow(self) -> numpy.typing.NDArray[numpy.int32]: ... + @nrow.setter + def nrow(self, arg1: typing.Any) -> None: ... + @property + def size(self) -> numpy.typing.NDArray[numpy.float64]: ... + @size.setter + def size(self, arg1: typing.Any) -> None: ... + +class _MjModelJointViews: + def __repr__(self) -> str: ... + @property + def M0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @M0.setter + def M0(self, arg1: typing.Any) -> None: ... + @property + def Madr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @Madr.setter + def Madr(self, arg1: typing.Any) -> None: ... + @property + def armature(self) -> numpy.typing.NDArray[numpy.float64]: ... + @armature.setter + def armature(self, arg1: typing.Any) -> None: ... + @property + def axis(self) -> numpy.typing.NDArray[numpy.float64]: ... + @axis.setter + def axis(self, arg1: typing.Any) -> None: ... + @property + def bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bodyid.setter + def bodyid(self, arg1: typing.Any) -> None: ... + @property + def damping(self) -> numpy.typing.NDArray[numpy.float64]: ... + @damping.setter + def damping(self, arg1: typing.Any) -> None: ... + @property + def dofadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dofadr.setter + def dofadr(self, arg1: typing.Any) -> None: ... + @property + def frictionloss(self) -> numpy.typing.NDArray[numpy.float64]: ... + @frictionloss.setter + def frictionloss(self, arg1: typing.Any) -> None: ... + @property + def group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @group.setter + def group(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def invweight0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @invweight0.setter + def invweight0(self, arg1: typing.Any) -> None: ... + @property + def jntid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @jntid.setter + def jntid(self, arg1: typing.Any) -> None: ... + @property + def limited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @limited.setter + def limited(self, arg1: typing.Any) -> None: ... + @property + def margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @margin.setter + def margin(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def parentid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @parentid.setter + def parentid(self, arg1: typing.Any) -> None: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def qpos0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qpos0.setter + def qpos0(self, arg1: typing.Any) -> None: ... + @property + def qpos_spring(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qpos_spring.setter + def qpos_spring(self, arg1: typing.Any) -> None: ... + @property + def qposadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @qposadr.setter + def qposadr(self, arg1: typing.Any) -> None: ... + @property + def range(self) -> numpy.typing.NDArray[numpy.float64]: ... + @range.setter + def range(self, arg1: typing.Any) -> None: ... + @property + def simplenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @simplenum.setter + def simplenum(self, arg1: typing.Any) -> None: ... + @property + def solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solimp.setter + def solimp(self, arg1: typing.Any) -> None: ... + @property + def solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solref.setter + def solref(self, arg1: typing.Any) -> None: ... + @property + def stiffness(self) -> numpy.typing.NDArray[numpy.float64]: ... + @stiffness.setter + def stiffness(self, arg1: typing.Any) -> None: ... + @property + def type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @type.setter + def type(self, arg1: typing.Any) -> None: ... + @property + def user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @user.setter + def user(self, arg1: typing.Any) -> None: ... + +class _MjModelKeyframeViews: + def __repr__(self) -> str: ... + @property + def act(self) -> numpy.typing.NDArray[numpy.float64]: ... + @act.setter + def act(self, arg1: typing.Any) -> None: ... + @property + def ctrl(self) -> numpy.typing.NDArray[numpy.float64]: ... + @ctrl.setter + def ctrl(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def mpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mpos.setter + def mpos(self, arg1: typing.Any) -> None: ... + @property + def mquat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @mquat.setter + def mquat(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def qpos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qpos.setter + def qpos(self, arg1: typing.Any) -> None: ... + @property + def qvel(self) -> numpy.typing.NDArray[numpy.float64]: ... + @qvel.setter + def qvel(self, arg1: typing.Any) -> None: ... + @property + def time(self) -> numpy.typing.NDArray[numpy.float64]: ... + @time.setter + def time(self, arg1: typing.Any) -> None: ... + +class _MjModelLightViews: + def __repr__(self) -> str: ... + @property + def active(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @active.setter + def active(self, arg1: typing.Any) -> None: ... + @property + def ambient(self) -> numpy.typing.NDArray[numpy.float32]: ... + @ambient.setter + def ambient(self, arg1: typing.Any) -> None: ... + @property + def attenuation(self) -> numpy.typing.NDArray[numpy.float32]: ... + @attenuation.setter + def attenuation(self, arg1: typing.Any) -> None: ... + @property + def bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bodyid.setter + def bodyid(self, arg1: typing.Any) -> None: ... + @property + def castshadow(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @castshadow.setter + def castshadow(self, arg1: typing.Any) -> None: ... + @property + def cutoff(self) -> numpy.typing.NDArray[numpy.float32]: ... + @cutoff.setter + def cutoff(self, arg1: typing.Any) -> None: ... + @property + def diffuse(self) -> numpy.typing.NDArray[numpy.float32]: ... + @diffuse.setter + def diffuse(self, arg1: typing.Any) -> None: ... + @property + def dir(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dir.setter + def dir(self, arg1: typing.Any) -> None: ... + @property + def dir0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @dir0.setter + def dir0(self, arg1: typing.Any) -> None: ... + @property + def exponent(self) -> numpy.typing.NDArray[numpy.float32]: ... + @exponent.setter + def exponent(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def mode(self) -> numpy.typing.NDArray[numpy.int32]: ... + @mode.setter + def mode(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def pos0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos0.setter + def pos0(self, arg1: typing.Any) -> None: ... + @property + def poscom0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @poscom0.setter + def poscom0(self, arg1: typing.Any) -> None: ... + @property + def specular(self) -> numpy.typing.NDArray[numpy.float32]: ... + @specular.setter + def specular(self, arg1: typing.Any) -> None: ... + @property + def targetbodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @targetbodyid.setter + def targetbodyid(self, arg1: typing.Any) -> None: ... + @property + def type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @type.setter + def type(self, arg1: typing.Any) -> None: ... + +class _MjModelMaterialViews: + def __repr__(self) -> str: ... + @property + def emission(self) -> numpy.typing.NDArray[numpy.float32]: ... + @emission.setter + def emission(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def reflectance(self) -> numpy.typing.NDArray[numpy.float32]: ... + @reflectance.setter + def reflectance(self, arg1: typing.Any) -> None: ... + @property + def rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @rgba.setter + def rgba(self, arg1: typing.Any) -> None: ... + @property + def shininess(self) -> numpy.typing.NDArray[numpy.float32]: ... + @shininess.setter + def shininess(self, arg1: typing.Any) -> None: ... + @property + def specular(self) -> numpy.typing.NDArray[numpy.float32]: ... + @specular.setter + def specular(self, arg1: typing.Any) -> None: ... + @property + def texid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @texid.setter + def texid(self, arg1: typing.Any) -> None: ... + @property + def texrepeat(self) -> numpy.typing.NDArray[numpy.float32]: ... + @texrepeat.setter + def texrepeat(self, arg1: typing.Any) -> None: ... + @property + def texuniform(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @texuniform.setter + def texuniform(self, arg1: typing.Any) -> None: ... + +class _MjModelMeshViews: + def __repr__(self) -> str: ... + @property + def faceadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @faceadr.setter + def faceadr(self, arg1: typing.Any) -> None: ... + @property + def facenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @facenum.setter + def facenum(self, arg1: typing.Any) -> None: ... + @property + def graphadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @graphadr.setter + def graphadr(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def texcoordadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @texcoordadr.setter + def texcoordadr(self, arg1: typing.Any) -> None: ... + @property + def vertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @vertadr.setter + def vertadr(self, arg1: typing.Any) -> None: ... + @property + def vertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @vertnum.setter + def vertnum(self, arg1: typing.Any) -> None: ... + +class _MjModelNumericViews: + def __repr__(self) -> str: ... + @property + def adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @adr.setter + def adr(self, arg1: typing.Any) -> None: ... + @property + def data(self) -> numpy.typing.NDArray[numpy.float64]: ... + @data.setter + def data(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def size(self) -> numpy.typing.NDArray[numpy.int32]: ... + @size.setter + def size(self, arg1: typing.Any) -> None: ... + +class _MjModelPairViews: + def __repr__(self) -> str: ... + @property + def dim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dim.setter + def dim(self, arg1: typing.Any) -> None: ... + @property + def friction(self) -> numpy.typing.NDArray[numpy.float64]: ... + @friction.setter + def friction(self, arg1: typing.Any) -> None: ... + @property + def gap(self) -> numpy.typing.NDArray[numpy.float64]: ... + @gap.setter + def gap(self, arg1: typing.Any) -> None: ... + @property + def geom1(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom1.setter + def geom1(self, arg1: typing.Any) -> None: ... + @property + def geom2(self) -> numpy.typing.NDArray[numpy.int32]: ... + @geom2.setter + def geom2(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @margin.setter + def margin(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def signature(self) -> numpy.typing.NDArray[numpy.int32]: ... + @signature.setter + def signature(self, arg1: typing.Any) -> None: ... + @property + def solimp(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solimp.setter + def solimp(self, arg1: typing.Any) -> None: ... + @property + def solref(self) -> numpy.typing.NDArray[numpy.float64]: ... + @solref.setter + def solref(self, arg1: typing.Any) -> None: ... + +class _MjModelSensorViews: + def __repr__(self) -> str: ... + @property + def adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @adr.setter + def adr(self, arg1: typing.Any) -> None: ... + @property + def cutoff(self) -> numpy.typing.NDArray[numpy.float64]: ... + @cutoff.setter + def cutoff(self, arg1: typing.Any) -> None: ... + @property + def datatype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @datatype.setter + def datatype(self, arg1: typing.Any) -> None: ... + @property + def dim(self) -> numpy.typing.NDArray[numpy.int32]: ... + @dim.setter + def dim(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def needstage(self) -> numpy.typing.NDArray[numpy.int32]: ... + @needstage.setter + def needstage(self, arg1: typing.Any) -> None: ... + @property + def noise(self) -> numpy.typing.NDArray[numpy.float64]: ... + @noise.setter + def noise(self, arg1: typing.Any) -> None: ... + @property + def objid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @objid.setter + def objid(self, arg1: typing.Any) -> None: ... + @property + def objtype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @objtype.setter + def objtype(self, arg1: typing.Any) -> None: ... + @property + def refid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @refid.setter + def refid(self, arg1: typing.Any) -> None: ... + @property + def reftype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @reftype.setter + def reftype(self, arg1: typing.Any) -> None: ... + @property + def type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @type.setter + def type(self, arg1: typing.Any) -> None: ... + @property + def user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @user.setter + def user(self, arg1: typing.Any) -> None: ... + +class _MjModelSiteViews: + def __repr__(self) -> str: ... + @property + def bodyid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bodyid.setter + def bodyid(self, arg1: typing.Any) -> None: ... + @property + def group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @group.setter + def group(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @matid.setter + def matid(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def pos(self) -> numpy.typing.NDArray[numpy.float64]: ... + @pos.setter + def pos(self, arg1: typing.Any) -> None: ... + @property + def quat(self) -> numpy.typing.NDArray[numpy.float64]: ... + @quat.setter + def quat(self, arg1: typing.Any) -> None: ... + @property + def rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @rgba.setter + def rgba(self, arg1: typing.Any) -> None: ... + @property + def sameframe(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @sameframe.setter + def sameframe(self, arg1: typing.Any) -> None: ... + @property + def size(self) -> numpy.typing.NDArray[numpy.float64]: ... + @size.setter + def size(self, arg1: typing.Any) -> None: ... + @property + def type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @type.setter + def type(self, arg1: typing.Any) -> None: ... + @property + def user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @user.setter + def user(self, arg1: typing.Any) -> None: ... + +class _MjModelSkinViews: + def __repr__(self) -> str: ... + @property + def boneadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @boneadr.setter + def boneadr(self, arg1: typing.Any) -> None: ... + @property + def bonenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @bonenum.setter + def bonenum(self, arg1: typing.Any) -> None: ... + @property + def faceadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @faceadr.setter + def faceadr(self, arg1: typing.Any) -> None: ... + @property + def facenum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @facenum.setter + def facenum(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def inflate(self) -> numpy.typing.NDArray[numpy.float32]: ... + @inflate.setter + def inflate(self, arg1: typing.Any) -> None: ... + @property + def matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @matid.setter + def matid(self, arg1: typing.Any) -> None: ... + @property + def name(self) -> str: ... + @property + def rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @rgba.setter + def rgba(self, arg1: typing.Any) -> None: ... + @property + def texcoordadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @texcoordadr.setter + def texcoordadr(self, arg1: typing.Any) -> None: ... + @property + def vertadr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @vertadr.setter + def vertadr(self, arg1: typing.Any) -> None: ... + @property + def vertnum(self) -> numpy.typing.NDArray[numpy.int32]: ... + @vertnum.setter + def vertnum(self, arg1: typing.Any) -> None: ... + +class _MjModelTendonViews: + def __repr__(self) -> str: ... + @property + def _adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @_adr.setter + def _adr(self, arg1: typing.Any) -> None: ... + @property + def _damping(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_damping.setter + def _damping(self, arg1: typing.Any) -> None: ... + @property + def _frictionloss(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_frictionloss.setter + def _frictionloss(self, arg1: typing.Any) -> None: ... + @property + def _group(self) -> numpy.typing.NDArray[numpy.int32]: ... + @_group.setter + def _group(self, arg1: typing.Any) -> None: ... + @property + def _invweight0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_invweight0.setter + def _invweight0(self, arg1: typing.Any) -> None: ... + @property + def _length0(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_length0.setter + def _length0(self, arg1: typing.Any) -> None: ... + @property + def _lengthspring(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_lengthspring.setter + def _lengthspring(self, arg1: typing.Any) -> None: ... + @property + def _limited(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @_limited.setter + def _limited(self, arg1: typing.Any) -> None: ... + @property + def _margin(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_margin.setter + def _margin(self, arg1: typing.Any) -> None: ... + @property + def _matid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @_matid.setter + def _matid(self, arg1: typing.Any) -> None: ... + @property + def _num(self) -> numpy.typing.NDArray[numpy.int32]: ... + @_num.setter + def _num(self, arg1: typing.Any) -> None: ... + @property + def _range(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_range.setter + def _range(self, arg1: typing.Any) -> None: ... + @property + def _rgba(self) -> numpy.typing.NDArray[numpy.float32]: ... + @_rgba.setter + def _rgba(self, arg1: typing.Any) -> None: ... + @property + def _solimp_fri(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_solimp_fri.setter + def _solimp_fri(self, arg1: typing.Any) -> None: ... + @property + def _solimp_lim(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_solimp_lim.setter + def _solimp_lim(self, arg1: typing.Any) -> None: ... + @property + def _solref_fri(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_solref_fri.setter + def _solref_fri(self, arg1: typing.Any) -> None: ... + @property + def _solref_lim(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_solref_lim.setter + def _solref_lim(self, arg1: typing.Any) -> None: ... + @property + def _stiffness(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_stiffness.setter + def _stiffness(self, arg1: typing.Any) -> None: ... + @property + def _user(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_user.setter + def _user(self, arg1: typing.Any) -> None: ... + @property + def _width(self) -> numpy.typing.NDArray[numpy.float64]: ... + @_width.setter + def _width(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + +class _MjModelTextureViews: + def __repr__(self) -> str: ... + @property + def adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @adr.setter + def adr(self, arg1: typing.Any) -> None: ... + @property + def data(self) -> numpy.typing.NDArray[numpy.uint8]: ... + @data.setter + def data(self, arg1: typing.Any) -> None: ... + @property + def height(self) -> numpy.typing.NDArray[numpy.int32]: ... + @height.setter + def height(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def nchannel(self) -> numpy.typing.NDArray[numpy.int32]: ... + @nchannel.setter + def nchannel(self, arg1: typing.Any) -> None: ... + @property + def type(self) -> numpy.typing.NDArray[numpy.int32]: ... + @type.setter + def type(self, arg1: typing.Any) -> None: ... + @property + def width(self) -> numpy.typing.NDArray[numpy.int32]: ... + @width.setter + def width(self, arg1: typing.Any) -> None: ... + +class _MjModelTupleViews: + def __repr__(self) -> str: ... + @property + def adr(self) -> numpy.typing.NDArray[numpy.int32]: ... + @adr.setter + def adr(self, arg1: typing.Any) -> None: ... + @property + def id(self) -> int: ... + @property + def name(self) -> str: ... + @property + def objid(self) -> numpy.typing.NDArray[numpy.int32]: ... + @objid.setter + def objid(self, arg1: typing.Any) -> None: ... + @property + def objprm(self) -> numpy.typing.NDArray[numpy.float64]: ... + @objprm.setter + def objprm(self, arg1: typing.Any) -> None: ... + @property + def objtype(self) -> numpy.typing.NDArray[numpy.int32]: ... + @objtype.setter + def objtype(self, arg1: typing.Any) -> None: ... + @property + def size(self) -> numpy.typing.NDArray[numpy.int32]: ... + @size.setter + def size(self, arg1: typing.Any) -> None: ... + +class _MjSolverStatList: + __hash__: typing.ClassVar[None] = None + def __eq__(self, arg0: typing.Any) -> bool: ... + @typing.overload + def __getitem__(self, arg0: typing.SupportsInt) -> MjSolverStat: ... + @typing.overload + def __getitem__(self, arg0: slice) -> _MjSolverStatList: ... + def __len__(self) -> int: ... + def __repr__(self) -> str: ... + @property + def gradient(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def improvement(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def lineslope(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def nactive(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def nchange(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def neval(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def nupdate(self) -> numpy.typing.NDArray[numpy.int32]: ... + +class _MjTimerStatList: + __hash__: typing.ClassVar[None] = None + def __eq__(self, arg0: typing.Any) -> bool: ... + @typing.overload + def __getitem__(self, arg0: typing.SupportsInt) -> MjTimerStat: ... + @typing.overload + def __getitem__(self, arg0: mujoco._enums.mjtTimer) -> MjTimerStat: ... + @typing.overload + def __getitem__(self, arg0: slice) -> _MjTimerStatList: ... + def __len__(self) -> int: ... + def __repr__(self) -> str: ... + @property + def duration(self) -> numpy.typing.NDArray[numpy.float64]: ... + @property + def number(self) -> numpy.typing.NDArray[numpy.int32]: ... + +class _MjWarningStatList: + __hash__: typing.ClassVar[None] = None + def __eq__(self, arg0: typing.Any) -> bool: ... + @typing.overload + def __getitem__(self, arg0: typing.SupportsInt) -> MjWarningStat: ... + @typing.overload + def __getitem__(self, arg0: mujoco._enums.mjtWarning) -> MjWarningStat: ... + @typing.overload + def __getitem__(self, arg0: slice) -> _MjWarningStatList: ... + def __len__(self) -> int: ... + def __repr__(self) -> str: ... + @property + def lastinfo(self) -> numpy.typing.NDArray[numpy.int32]: ... + @property + def number(self) -> numpy.typing.NDArray[numpy.int32]: ... + +def _recompile_spec_addr( + arg0: typing.SupportsInt, arg1: MjModel, arg2: MjData +) -> tuple: ... +def mjv_averageCamera(cam1: MjvGLCamera, cam2: MjvGLCamera) -> MjvGLCamera: + """ + Return the average of two OpenGL cameras. + """ diff --git a/typings/mujoco/gl_context.pyi b/typings/mujoco/gl_context.pyi new file mode 100644 index 000000000..fcc49ca2f --- /dev/null +++ b/typings/mujoco/gl_context.pyi @@ -0,0 +1,26 @@ +""" +Exports GLContext for MuJoCo Python bindings. +""" + +from __future__ import annotations +import ctypes as ctypes +from mujoco.glfw import GLContext +from mujoco.glfw import GLContext as _GLContext +import os as os +import platform as platform + +__all__: list[str] = ["GLContext", "ctypes", "os", "platform"] +_MUJOCO_GL: str = "" +_SYSTEM: str = "Linux" +_VALID_MUJOCO_GL: tuple = ( + "enable", + "enabled", + "on", + "true", + "1", + "glfw", + "", + "glx", + "egl", + "osmesa", +) diff --git a/typings/mujoco/glfw/__init__.pyi b/typings/mujoco/glfw/__init__.pyi new file mode 100644 index 000000000..c7412c4b1 --- /dev/null +++ b/typings/mujoco/glfw/__init__.pyi @@ -0,0 +1,17 @@ +""" +An OpenGL context created via GLFW. +""" + +from __future__ import annotations +import glfw as glfw + +__all__: list[str] = ["GLContext", "glfw"] + +class GLContext: + """ + An OpenGL context created via GLFW. + """ + def __del__(self): ... + def __init__(self, max_width, max_height): ... + def free(self): ... + def make_current(self): ... diff --git a/typings/mujoco/renderer.pyi b/typings/mujoco/renderer.pyi new file mode 100644 index 000000000..e2c2a3cee --- /dev/null +++ b/typings/mujoco/renderer.pyi @@ -0,0 +1,117 @@ +""" +Defines a renderer class for the MuJoCo Python native bindings. +""" + +from __future__ import annotations +from mujoco import _enums +import mujoco._enums +from mujoco import _functions +from mujoco import _render +from mujoco import _structs +import mujoco._structs +from mujoco import gl_context +import numpy as np +import numpy + +__all__: list[str] = ["Renderer", "gl_context", "np"] + +class Renderer: + """ + Renders MuJoCo scenes. + """ + def __del__(self) -> None: ... + def __enter__(self): ... + def __exit__(self, exc_type, exc_value, traceback): ... + def __init__( + self, + model: mujoco._structs.MjModel, + height: int = 240, + width: int = 320, + max_geom: int = 10000, + font_scale: mujoco._enums.mjtFontScale = ..., + ) -> None: + """ + Initializes a new `Renderer`. + + Args: + model: an MjModel instance. + height: image height in pixels. + width: image width in pixels. + max_geom: Optional integer specifying the maximum number of geoms that can + be rendered in the same scene. If None this will be chosen automatically + based on the estimated maximum number of renderable geoms in the model. + font_scale: Optional enum specifying the font scale for text. + + Raises: + ValueError: If `camera_id` is outside the valid range, or if `width` or + `height` exceed the dimensions of MuJoCo's offscreen framebuffer. + """ + def close(self) -> None: + """ + Frees the resources used by the renderer. + + This method can be used directly: + + ```python + renderer = Renderer(...) + # Use renderer. + renderer.close() + ``` + + or via a context manager: + + ```python + with Renderer(...) as renderer: + # Use renderer. + ``` + """ + def disable_depth_rendering(self): ... + def disable_segmentation_rendering(self): ... + def enable_depth_rendering(self): ... + def enable_segmentation_rendering(self): ... + def render(self, *, out: typing.Optional[numpy.ndarray] = None) -> numpy.ndarray: + """ + Renders the scene as a numpy array of pixel values. + + Args: + out: Alternative output array in which to place the resulting pixels. It + must have the same shape as the expected output but the type will be + cast if necessary. The expted shape depends on the value of + `self._depth_rendering`: when `True`, we expect `out.shape == (width, + height)`, and `out.shape == (width, height, 3)` when `False`. + + Returns: + A new numpy array holding the pixels with shape `(H, W)` or `(H, W, 3)`, + depending on the value of `self._depth_rendering` unless + `out is None`, in which case a reference to `out` is returned. + + Raises: + RuntimeError: if this method is called after the close method. + """ + def update_scene( + self, + data: mujoco._structs.MjData, + camera: typing.Union[int, str, mujoco._structs.MjvCamera] = -1, + scene_option: typing.Optional[mujoco._structs.MjvOption] = None, + ): + """ + Updates geometry used for rendering. + + Args: + data: An instance of `MjData`. + camera: An instance of `MjvCamera`, a string or an integer + scene_option: A custom `MjvOption` instance to use to render the scene + instead of the default. + + Raises: + ValueError: If `camera_id` is outside the valid range, or if camera does + not exist. + """ + @property + def height(self): ... + @property + def model(self): ... + @property + def scene(self) -> mujoco._structs.MjvScene: ... + @property + def width(self): ... diff --git a/typings/mujoco/viewer.pyi b/typings/mujoco/viewer.pyi new file mode 100644 index 000000000..7f25eef6f --- /dev/null +++ b/typings/mujoco/viewer.pyi @@ -0,0 +1,290 @@ +""" +Interactive GUI viewer for MuJoCo. +""" + +from __future__ import annotations +import abc as abc +import atexit as atexit +import contextlib as contextlib +import glfw as glfw +import math as math +import mujoco as mujoco +from mujoco import _simulate +from mujoco._simulate import Simulate as _Simulate +import numpy as np +import os as os +import queue as queue +import sys as sys +import threading as threading +import time as time +import typing +import weakref as weakref + +__all__: list[str] = [ + "CallbackType", + "Handle", + "KeyCallbackType", + "LoaderType", + "MAX_SYNC_MISALIGN", + "PERCENT_REALTIME", + "SIM_REFRESH_FRACTION", + "abc", + "atexit", + "contextlib", + "glfw", + "launch", + "launch_from_path", + "launch_passive", + "math", + "mujoco", + "np", + "os", + "queue", + "sys", + "threading", + "time", + "weakref", +] + +class Handle: + """ + A handle for interacting with a MuJoCo viewer. + """ + def __enter__(self): ... + def __exit__(self, exc_type, exc_val, exc_tb): ... + def __init__( + self, + sim: mujoco._simulate.Simulate, + cam: mujoco._structs.MjvCamera, + opt: mujoco._structs.MjvOption, + pert: mujoco._structs.MjvPerturb, + user_scn: typing.Optional[mujoco._structs.MjvScene], + ): ... + def _get_sim(self) -> typing.Optional[mujoco._simulate.Simulate]: ... + def clear_figures(self): ... + def clear_images(self): ... + def clear_texts(self): ... + def close(self): ... + def is_running(self) -> bool: ... + def lock(self): ... + def set_figures( + self, + viewports_figures: typing.Union[ + typing.Tuple[mujoco._render.MjrRect, mujoco._structs.MjvFigure], + typing.List[typing.Tuple[mujoco._render.MjrRect, mujoco._structs.MjvFigure]], + ], + ): + """ + Overlay figures on the viewer. + + Args: + viewports_figures: Single tuple or list of tuples of (viewport, figure) + viewport: Rectangle defining position and size of the figure + figure: MjvFigure object containing the figure data to display + """ + def set_images( + self, + viewports_images: typing.Union[ + typing.Tuple[mujoco._render.MjrRect, numpy.ndarray], + typing.List[typing.Tuple[mujoco._render.MjrRect, numpy.ndarray]], + ], + ): + """ + Overlay images on the viewer. + + Args: + viewports_images: Single tuple or list of tuples of (viewport, image) + viewport: Rectangle defining position and size of the image + image: RGB image with shape (height, width, 3) + """ + def set_texts( + self, + texts: typing.Union[ + typing.Tuple[ + typing.Optional[int], + typing.Optional[int], + typing.Optional[str], + typing.Optional[str], + ], + typing.List[ + typing.Tuple[ + typing.Optional[int], + typing.Optional[int], + typing.Optional[str], + typing.Optional[str], + ] + ], + ], + ): + """ + Overlay text on the viewer. + + Args: + texts: Single tuple or list of tuples of (font, gridpos, text1, text2) + font: Font style from mujoco.mjtFontScale + gridpos: Position of text box from mujoco.mjtGridPos + text1: Left text column, defaults to empty string if None + text2: Right text column, defaults to empty string if None + """ + def sync(self, state_only: bool = False): ... + def update_hfield(self, hfieldid: int): ... + def update_mesh(self, meshid: int): ... + def update_texture(self, texid: int): ... + @property + def cam(self): ... + @property + def d(self): ... + @property + def m(self): ... + @property + def opt(self): ... + @property + def perturb(self): ... + @property + def user_scn(self): ... + @property + def viewport(self): ... + +class _MjPythonBase: + __abstractmethods__: typing.ClassVar[frozenset] # value = frozenset() + _abc_impl: typing.ClassVar[_abc._abc_data] # value = <_abc._abc_data object> + def launch_on_ui_thread( + self, + model: mujoco._structs.MjModel, + data: mujoco._structs.MjData, + handle_return: typing.Optional[ForwardRef("queue.Queue[Handle]")], + key_callback: typing.Optional[typing.Callable[[int], NoneType]], + ): ... + +def _file_loader( + path: str, +) -> typing.Callable[ + [], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData, str] +]: + """ + Loads an MJCF model from file path. + """ + +def _launch_internal( + model: typing.Optional[mujoco._structs.MjModel] = None, + data: typing.Optional[mujoco._structs.MjData] = None, + *, + run_physics_thread: bool, + loader: typing.Union[ + typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData]], + typing.Callable[ + [], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData, str] + ], + NoneType, + ] = None, + handle_return: typing.Optional[ForwardRef("queue.Queue[Handle]")] = None, + key_callback: typing.Optional[typing.Callable[[int], NoneType]] = None, + show_left_ui: bool = True, + show_right_ui: bool = True, +) -> None: + """ + Internal API, so that the public API has more readable type annotations. + """ + +def _physics_loop( + simulate: mujoco._simulate.Simulate, + loader: typing.Union[ + typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData]], + typing.Callable[ + [], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData, str] + ], + NoneType, + ], +): + """ + Physics loop for the GUI, to be run in a separate thread. + """ + +def _reload( + simulate: mujoco._simulate.Simulate, + loader: typing.Union[ + typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData]], + typing.Callable[ + [], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData, str] + ], + ], + notify_loaded: typing.Optional[typing.Callable[[], NoneType]] = None, +) -> typing.Optional[typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData]]: + """ + Internal function for reloading a model in the viewer. + """ + +def launch( + model: typing.Optional[mujoco._structs.MjModel] = None, + data: typing.Optional[mujoco._structs.MjData] = None, + *, + loader: typing.Optional[ + typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData]] + ] = None, + show_left_ui: bool = True, + show_right_ui: bool = True, +) -> None: + """ + Launches the Simulate GUI. + """ + +def launch_from_path(path: str) -> None: + """ + Launches the Simulate GUI from file path. + """ + +def launch_passive( + model: mujoco._structs.MjModel, + data: mujoco._structs.MjData, + *, + key_callback: typing.Optional[typing.Callable[[int], NoneType]] = None, + show_left_ui: bool = True, + show_right_ui: bool = True, +) -> Handle: + """ + Launches a passive Simulate GUI without blocking the running thread. + """ + +CallbackType: typing._CallableGenericAlias # value = typing.Callable[[mujoco._structs.MjModel, mujoco._structs.MjData], NoneType] +KeyCallbackType: ( + typing._CallableGenericAlias +) # value = typing.Callable[[int], NoneType] +LoaderType: typing._CallableGenericAlias # value = typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData]] +MAX_SYNC_MISALIGN: float = 0.1 +PERCENT_REALTIME: tuple = ( + 100, + 80, + 66, + 50, + 40, + 33, + 25, + 20, + 16, + 13, + 10, + 8, + 6.6, + 5, + 4, + 3.3, + 2.5, + 2, + 1.6, + 1.3, + 1, + 0.8, + 0.66, + 0.5, + 0.4, + 0.33, + 0.25, + 0.2, + 0.16, + 0.13, + 0.1, +) +SIM_REFRESH_FRACTION: float = 0.7 +_InternalLoaderType: typing._UnionGenericAlias # value = typing.Union[typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData]], typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData, str]]] +_LoaderWithPathType: typing._CallableGenericAlias # value = typing.Callable[[], typing.Tuple[mujoco._structs.MjModel, mujoco._structs.MjData, str]] +_MJPYTHON = None diff --git a/uv.lock b/uv.lock index badc16622..7ed2759a7 100644 --- a/uv.lock +++ b/uv.lock @@ -800,14 +800,18 @@ version = "0.0.0" source = { editable = "." } dependencies = [ { name = "gymnasium" }, + { name = "moviepy" }, { name = "mujoco" }, { name = "mujoco-warp" }, { name = "prettytable" }, + { name = "rsl-rl-lib" }, + { name = "tensordict" }, { name = "torch" }, { name = "tqdm" }, { name = "trimesh" }, { name = "tyro" }, { name = "viser" }, + { name = "wandb" }, { name = "warp-lang", version = "1.8.1", source = { registry = "https://pypi.org/simple" }, marker = "sys_platform == 'darwin'" }, { name = "warp-lang", version = "1.9.0.dev20250819", source = { registry = "https://pypi.nvidia.com/" }, marker = "sys_platform != 'darwin'" }, ] @@ -820,16 +824,15 @@ rl = [ { name = "moviepy" }, { name = "rsl-rl-lib" }, { name = "tensorboard" }, - { name = "wandb" }, ] [package.dev-dependencies] dev = [ { name = "absl-py" }, { name = "pre-commit" }, + { name = "pyright" }, { name = "pytest" }, { name = "ruff" }, - { name = "ty" }, ] lint = [ { name = "ruff" }, @@ -842,19 +845,22 @@ test = [ [package.metadata] requires-dist = [ { name = "gymnasium", specifier = "==1.2.0" }, + { name = "moviepy" }, { name = "moviepy", marker = "extra == 'rl'", specifier = ">=1.0.0" }, { name = "mujoco", index = "https://py.mujoco.org/" }, { name = "mujoco-warp", git = "https://github.com/google-deepmind/mujoco_warp" }, { name = "prettytable" }, + { name = "rsl-rl-lib" }, { name = "rsl-rl-lib", marker = "extra == 'rl'" }, { name = "tensorboard", marker = "extra == 'rl'" }, + { name = "tensordict" }, { name = "torch" }, { name = "torch", marker = "extra == 'cu12'", specifier = ">=2.7.0", index = "https://download.pytorch.org/whl/cu128", conflict = { package = "mjlab", extra = "cu12" } }, { name = "tqdm" }, { name = "trimesh" }, { name = "tyro" }, { name = "viser" }, - { name = "wandb", marker = "extra == 'rl'" }, + { name = "wandb" }, { name = "warp-lang", marker = "sys_platform != 'darwin'", index = "https://pypi.nvidia.com/" }, { name = "warp-lang", marker = "sys_platform == 'darwin'" }, ] @@ -864,9 +870,9 @@ provides-extras = ["cu12", "rl"] dev = [ { name = "absl-py" }, { name = "pre-commit" }, + { name = "pyright", specifier = ">=1.1.386" }, { name = "pytest" }, { name = "ruff" }, - { name = "ty" }, ] lint = [{ name = "ruff" }] test = [ @@ -1777,6 +1783,19 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/92/44/8634af40b0db528b5b37e901c0dc67321354880d251bf8965901d57693a5/PyOpenGL-3.1.9-py3-none-any.whl", hash = "sha256:15995fd3b0deb991376805da36137a4ae5aba6ddbb5e29ac1f35462d130a3f77", size = 3190341, upload-time = "2025-01-20T02:17:50.913Z" }, ] +[[package]] +name = "pyright" +version = "1.1.404" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "nodeenv" }, + { name = "typing-extensions" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/e2/6e/026be64c43af681d5632722acd100b06d3d39f383ec382ff50a71a6d5bce/pyright-1.1.404.tar.gz", hash = "sha256:455e881a558ca6be9ecca0b30ce08aa78343ecc031d37a198ffa9a7a1abeb63e", size = 4065679, upload-time = "2025-08-20T18:46:14.029Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/84/30/89aa7f7d7a875bbb9a577d4b1dc5a3e404e3d2ae2657354808e905e358e0/pyright-1.1.404-py3-none-any.whl", hash = "sha256:c7b7ff1fdb7219c643079e4c3e7d4125f0dafcc19d253b47e898d130ea426419", size = 5902951, upload-time = "2025-08-20T18:46:12.096Z" }, +] + [[package]] name = "pytest" version = "8.4.1" @@ -2704,31 +2723,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/20/63/8cb444ad5cdb25d999b7d647abac25af0ee37d292afc009940c05b82dda0/triton-3.4.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7936b18a3499ed62059414d7df563e6c163c5e16c3773678a3ee3d417865035d", size = 155659780, upload-time = "2025-07-30T19:58:51.171Z" }, ] -[[package]] -name = "ty" -version = "0.0.1a18" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/84/17/6f74949ef1686a8933fab8d11b0e6c2925235b02d513bd0aea49ab717609/ty-0.0.1a18.tar.gz", hash = "sha256:f213e6d8ab3b6abaeb76aa66c6c5c9ad04d7d21a80b4111422286e4beff6d294", size = 4079761, upload-time = "2025-08-14T10:32:18.833Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/71/6b/9b6480d9cff51a8d1346950194363ac269f883771e4f53bd3cb55bd79b93/ty-0.0.1a18-py3-none-linux_armv6l.whl", hash = "sha256:f1fe54d817294f18e29a164ad8c460c7cdf60251ef392733a8afcfb6db5e933b", size = 8107401, upload-time = "2025-08-14T10:31:44.691Z" }, - { url = "https://files.pythonhosted.org/packages/c5/1e/a02beb69386416da8b44b12b9cd32c55ac6f72361f70048d811c7efc2dff/ty-0.0.1a18-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:fb40403157f2c7fd81d15c6745932daa486cd7954c2721e5dc22c0a5d0415add", size = 8304302, upload-time = "2025-08-14T10:31:46.819Z" }, - { url = "https://files.pythonhosted.org/packages/d0/00/421bad42f962dd29cf16c7d941a10a39dc1f9d7906e186a098c75cb0a6aa/ty-0.0.1a18-py3-none-macosx_11_0_arm64.whl", hash = "sha256:07f310f21416e50d726f68fb213266576fab18a977bd76bc57e852551427b5a1", size = 7883646, upload-time = "2025-08-14T10:31:49.449Z" }, - { url = "https://files.pythonhosted.org/packages/92/f1/e7069f8914e2b700709567f24e19221623e35e0c21fa474a5c568ce9485a/ty-0.0.1a18-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fdbd9bbe7a44f467c0f21171aada32f7a05a5aecc4e20c9a53ae888916589014", size = 8020426, upload-time = "2025-08-14T10:31:51.259Z" }, - { url = "https://files.pythonhosted.org/packages/68/d5/81ef03cf47554f6b080ab1d549275b7411631a412feab34da20c21c0c17d/ty-0.0.1a18-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:5ab463dc1a51f294b01b8b6fe869893a441df05590ac1edd4c76f154d1fc0b5a", size = 7933541, upload-time = "2025-08-14T10:31:53.074Z" }, - { url = "https://files.pythonhosted.org/packages/e2/3e/c131f9774ed8d8e048786e8005d3f70ffe09b536fab33b60b98b67f17fe5/ty-0.0.1a18-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4a6256b657ce45cd9b0173f1b8f858ff5ff1fef9314b1e167fcf53eb0c84d166", size = 8870017, upload-time = "2025-08-14T10:31:54.911Z" }, - { url = "https://files.pythonhosted.org/packages/3e/23/f75594959c952a63e94f6c97d830fb0975ff877def40b7016d448eaaf2a2/ty-0.0.1a18-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:0ed83cf7f4cc7ea9a40aed1cc0e19b6770b14d7b22fdbb9b65a68eb8ec11fe12", size = 9376017, upload-time = "2025-08-14T10:31:57.074Z" }, - { url = "https://files.pythonhosted.org/packages/ff/7c/3e843c781e2149731ce3b9a50a52ab98113041170901acb1f57bf78f142e/ty-0.0.1a18-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d4b3b7462bee0bc78b73124a19e47ca507ef609425310c3fa34bdf3257671618", size = 8990092, upload-time = "2025-08-14T10:31:59.023Z" }, - { url = "https://files.pythonhosted.org/packages/80/ae/7ac61ab4211d11d9596a541ab964d602e14126f124ec0b2c3a1300344642/ty-0.0.1a18-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9b0d83180dca1daf96fc46f2728cb5feadc867390b6d63e74aa9068eb3c85c13", size = 8776514, upload-time = "2025-08-14T10:32:01.171Z" }, - { url = "https://files.pythonhosted.org/packages/38/cd/16c04b8b93cb563990d27e65bf2def173909b7743b12df716974f492ba0b/ty-0.0.1a18-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8b5b4f8cd8fe3d1fe4e4b338570b8aee48889f5294a01d25d1b7a232a75b9fae", size = 8585311, upload-time = "2025-08-14T10:32:03.296Z" }, - { url = "https://files.pythonhosted.org/packages/6e/8d/56a4c49b68c3d37c35c76af377b7e55a4ead95680deef4929b539a4dae5f/ty-0.0.1a18-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:b64181d14e3d6b179860471cbe9e95a35d6d17919e73db6bef34b130de8f7c38", size = 7900949, upload-time = "2025-08-14T10:32:05.323Z" }, - { url = "https://files.pythonhosted.org/packages/88/0a/a4de919c09b8c1d5421069631f8f2d59e4db61c7aeef43cb4f342cb93d2e/ty-0.0.1a18-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:53cb0a37b007ed48eb104ea7e776ba84080a3c85ad118eea84e3f8d10644f9f6", size = 7956204, upload-time = "2025-08-14T10:32:08.056Z" }, - { url = "https://files.pythonhosted.org/packages/0c/e5/cb6cf1f1b6524a1c07173a27d58a9075fbf5c776f072b72448880ea8e419/ty-0.0.1a18-py3-none-musllinux_1_2_i686.whl", hash = "sha256:205f55224d6441ba36082fb9c0690088feba2b0d02dc8ebc11006afddd73a2fb", size = 8452269, upload-time = "2025-08-14T10:32:09.574Z" }, - { url = "https://files.pythonhosted.org/packages/9f/75/7152152a249613ccda535152d683a46a4e781737663a76154082a9eef2dd/ty-0.0.1a18-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:121032a844008e7f0e29590eadaa12ea4df2aa9c27c37f06943181c81025c920", size = 8650870, upload-time = "2025-08-14T10:32:11.37Z" }, - { url = "https://files.pythonhosted.org/packages/36/c0/f181a6cd2a6d6208f342950e241950e23dfa6218195469a304dae4fdf7fb/ty-0.0.1a18-py3-none-win32.whl", hash = "sha256:4ff87364366ce98d70eca7993a604e60f762b27156fc63a597aeb4f05e56be1c", size = 7789583, upload-time = "2025-08-14T10:32:13.115Z" }, - { url = "https://files.pythonhosted.org/packages/78/04/577495cd64b7e8ecd63fa3bb8c07cba11772f092b2a54c602b41acdabcf6/ty-0.0.1a18-py3-none-win_amd64.whl", hash = "sha256:596562ac1b67a3c4da2a895b5601a61babe9953b6fc3e6c66a6f6e1a2c2c5d60", size = 8422373, upload-time = "2025-08-14T10:32:14.653Z" }, - { url = "https://files.pythonhosted.org/packages/88/28/e7a9ec9195f3cfd76b95f1d01e7edecfe3be750c6f0f9cd3658625bedf07/ty-0.0.1a18-py3-none-win_arm64.whl", hash = "sha256:a557af5cf678485c77914da298621de751e86964d8d3237ee2229f5fce27ab35", size = 7968662, upload-time = "2025-08-14T10:32:16.386Z" }, -] - [[package]] name = "typeguard" version = "4.4.4"