PositionActionManager#

class genesis_forge.managers.action.PositionActionManager(env: GenesisEnv, actuator_manager: ActuatorManager | None = None, actuator_joints: list[str] | str = '.*', scale: float | dict[str, float] = 1.0, offset: float | dict[str, float] = 0.0, clip: tuple[float, float] | dict[str, tuple[float, float]] = None, use_default_offset: bool = True, action_handler: Callable[[torch.Tensor], None] = None, quiet_action_errors: bool = False, delay_step: int = 0, **kwargs)[source]#

Bases: BaseActionManager

Converts actions to DOF positions, using affine transformations (scale and offset).

\[position = offset + scaling * action\]

If use_default_offset is True, the offset will be set to the default_pos value for each DOF/joint.

Parameters:
  • env – The environment to manage the DOF actuators for.

  • actuator_manager – The actuator manager which is used to setup and control the DOF joints.

  • actuator_joints – Which joints of the actuator manager that this action manager will control. These can be full names or regular expressions.

  • scale – How much to scale the action.

  • offset – Offset factor for the action.

  • use_default_offset – Whether to use default joint positions configured in the articulation asset as offset. Defaults to True.

  • clip – Clip the action values to the range. If omitted, the action values will automatically be clipped to the joint limits.

  • quiet_action_errors – Whether to quiet action errors.

  • delay_step – The number of steps to delay the actions for. This is an easy way to emulate the latency in the system.

Example:

class MyEnv(ManagedEnvironment):
    def __init__(self, *args, **kwargs):
        super().__init__(*args, **kwargs)
        # ...define scene and robot...

    def config(self):
        self.actuator_manager = ActuatorManager(
            self,
            joint_names=".*",
            default_pos={".*": 0.0},
            kp=50,
            kv=0.5,
            max_force=8.0,
        )
        self.action_manager = PositionActionManager(
            self,
            scale=0.5,
            use_default_offset=True,
            actuator_manager=self.actuator_manager,
            actuator_joints=[".*"], # optional joint filter
        )

Example using the manager directly:

class MyEnv(GenesisEnv):
    def __init__(self, *args, **kwargs):
        super().__init__(*args, **kwargs)
        # ...define scene and robot...

        self.actuator_manager = ActuatorManager(
            self,
            joint_names=".*",
            default_pos={".*": 0.0},
            kp=50,
            kv=0.5,
            max_force=8.0,
        )
        self.action_manager = PositionActionManager(
            self,
            scale=0.5,
            offset=0.0,
            use_default_offset=True,
        )

    def build(self):
        super().build()
        self.actuator_manager.build()
        self.action_manager.build()

    step(self, actions: torch.Tensor) -> None:
        super().step(actions)
        self.action_manager.step(actions)

        # ...do other step things...

    reset(self, envs_idx: list[int] = None) -> None:
        super().reset(envs_idx)
        self.actuator_manager.reset(envs_idx)
        self.action_manager.reset(envs_idx)

        # ...do other reset things...
build()[source]#

Builds the manager and initialized all the buffers.

get_actions() torch.Tensor#

Get the current actions for the environments.

get_dofs_force(clip_to_max_force: bool = False)#

A wrapper for RigidEntity.get_dofs_force that returns the force experienced by the controlled DOFs.

Parameters:

clip_to_max_force – Clip the force returned to the maximum force defined by the max_force parameter defined in the actuator manager.

Returns:

torch.Tensor, shape (n_envs, n_dofs) The force experienced by the enabled DOFs.

Return type:

force

get_dofs_limits()#

A wrapper for RigidEntity.get_dofs_limit that returns the limits of the controlled DOFs.

Returns:

torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)

The lower limit of the positional limits for the entity’s dofs.

upper_limit: torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)

The upper limit of the positional limits for the entity’s dofs.

Return type:

lower_limit

get_dofs_position()#

A wrapper for RigidEntity.get_dofs_limits that returns the position limits of the controlled DOFs.

Returns:

tuple[torch.Tensor, torch.Tensor]

The position of the DOFs managed by this action manager.

Return type:

position

get_dofs_velocity(clip: tuple[float, float] = None)#

A wrapper for RigidEntity.get_dofs_velocity that returns the current velocity of the controlled DOFs.

Parameters:

clip – Range to clip the velocity to.

Returns:

torch.Tensor, shape (n_envs, n_dofs) The velocity of the enabled DOFs managed by this action manager.

Return type:

velocity

handle_actions(actions: torch.Tensor) torch.Tensor[source]#

Converts the actions to position commands, and send them to the DOF actuators. Override this function if you want to change the action handling logic.

Parameters:

actions – The incoming step actions to handle.

Returns:

The processed and handled actions.

reset(envs_idx: list[int] | None)#

Reset environments.

step(actions: torch.Tensor) torch.Tensor[source]#

Take the incoming actions for this step and handle them.

Parameters:

actions – The incoming step actions to handle.

property action_space: tuple[float, float]#

Returns the actions space for the environment, based on the number of DOFs defined in this action manager.

property actions: torch.Tensor#

The actions for for the current step.

property actuator_dof_filter: torch.Tensor#

An index filter for the actuator DOF buffer values.

property actuator_manager: ActuatorManager#

Get the actuator manager.

property actuators: ActuatorManager#
property default_dofs_pos: torch.Tensor#

Return the default DOF positions.

property dofs: dict[str, int]#

Get a dictionary of the DOF names and their indices

property dofs_idx: list[int]#

Get the indices of the DOFs that this action manager controls.

property num_actions: int#

Get the number of actions.

property raw_actions: torch.Tensor#

The actions received from the policy, before being converted.