Pipeline¶
This method gathers base implementations for blocks to be used in pipeline control design.
It implements:
the concept of block thats can be connected to a BaseJiminyEnv environment through multiple InterfaceJiminyEnv indirections
a base controller block, along with a concrete PD controller
a wrapper to combine a controller block and a BaseJiminyEnv environment, eventually already wrapped, so that it appears as a black-box environment.
- class gym_jiminy.common.bases.pipeline.BasePipelineWrapper(env, **kwargs)[source]¶
Bases:
InterfaceJiminyEnv
[ObsT
,ActT
],Generic
[ObsT
,ActT
,BaseObsT
,BaseActT
]Base class for wrapping a BaseJiminyEnv Gym environment so that it appears as a single, unified, environment. The environment may have been wrapped multiple times already.
If several successive blocks must be composed, just wrap each of them successively one by one.
Warning
Hot-plug of additional blocks is supported, but the environment need to be reset after changing the pipeline.
Warning
This architecture is not designed for trainable blocks, but rather for robotic-oriented controllers and observers, such as PID controllers, inverse kinematics, Model Predictive Control (MPC), sensor fusion… It is recommended to add the controllers and observers into the policy itself if they have to be trainable.
- Parameters:
env (InterfaceJiminyEnv[BaseObsT, BaseActT]) – Base or already wrapped jiminy environment.
kwargs (Any) – Extra keyword arguments for multiple inheritance.
- env: InterfaceJiminyEnv[BaseObsT, BaseActT]¶
- property np_random: Generator¶
Random number generator of the base environment.
- property unwrapped: BaseJiminyEnv¶
The “underlying environment at the basis of the pipeline from which this environment is part of.
- eval()[source]¶
Sets the environment in evaluation mode.
This only has an effect on certain environments. It can be used for instance to enable clipping or filtering of the action at evaluation time specifically. See documentations of a given environment for details about their behaviors in training and evaluation modes.
- Return type:
None
- reset(*, seed=None, options=None)[source]¶
Reset the unified environment.
In practice, it resets the environment and initializes the generic pipeline internal buffers through the use of ‘controller_hook’.
- step(action)[source]¶
Run a simulation step for a given action.
- Parameters:
action (ActT) – Next action to perform. None to not update it.
- Returns:
Next observation, reward, status of the episode (done or not), and a dictionary of extra information.
- Return type:
Tuple[Mapping[str, StructNested[ValueT]] | Iterable[StructNested[ValueT]] | ndarray, SupportsFloat, bool, bool, Dict[str, Any]]
- has_terminated(info)[source]¶
Determine whether the episode is over, because a terminal state of the underlying MDP has been reached or an aborting condition outside the scope of the MDP has been triggered.
By default, it does nothing but forwarding the request to the base environment. This behavior can be overwritten by the user.
Note
This method is called after refresh_observation, so that the internal buffer ‘observation’ is up-to-date.
- class gym_jiminy.common.bases.pipeline.ComposedJiminyEnv(env, *, reward=None, terminations=(), trajectories=None)[source]¶
Bases:
BasePipelineWrapper
[ObsT
,ActT
,ObsT
,ActT
],Generic
[ObsT
,ActT
]Extend an environment, eventually already wrapped, by plugging ad-hoc reward components and termination conditions, including their accompanying trajectory database if any.
This wrappers leaves unchanged the observation and action spaces of the environment. This can be done by adding observation and/or control blocks through ObservedJiminyEnv and ControlledJiminyEnv wrappers.
Note
This wrapper derives from BasePipelineWrapper, and such as, it is considered as internal unlike gym.Wrapper. This means that it will be taken into account when calling evaluate or play_interactive on the wrapped environment.
Warning
This class is final, ie not meant to be derived.
- Parameters:
env (InterfaceJiminyEnv[ObsT, ActT]) – Environment to extend, eventually already wrapped.
reward (AbstractReward | None) – Reward object deriving from AbstractReward. It will be evaluated at each step of the environment and summed up with the one returned by the wrapped environment. This reward must be already instantiated and associated with the provided environment. None for not considering any reward. Optional: None by default.
terminations (Sequence[AbstractTerminationCondition]) – Sequence of termination condition objects deriving from AbstractTerminationCondition. They will be checked along with the one enforced by the wrapped environment. If provided, these termination conditions must be already instantiated and associated with the environment at hands. Optional: Empty sequence by default.
trajectories (Dict[str, Trajectory] | None) – Set of named trajectories as a dictionary whose (key, value) pairs are respectively the name of each trajectory and the trajectory itself. None for not considering any trajectory. Optional: None by default.
- refresh_observation(measurement)[source]¶
Compute high-level features based on the current wrapped environment’s observation.
It simply forwards the observation computed by the wrapped environment without any processing.
- Parameters:
measurement (EngineObsType) – Low-level measure from the environment to process to get higher-level observation.
- Return type:
None
- has_terminated(info)[source]¶
Determine whether the practitioner is instructed to stop the ongoing episode on the spot because a termination condition has been triggered, either coming from the based environment or from the ad-hoc termination conditions that has been plugged on top of it.
At each step of the wrapped environment, all its termination conditions will be evaluated sequentially until one of them eventually gets triggered. If this happens, evaluation is skipped for the remaining ones and the reward is evaluated straight away. Ultimately, the practitioner is instructed to stop the ongoing episode, but it is his own responsibility to honor this request. The first condition being evaluated is the one of the underlying environment, then comes the ones of this composition layer, following the original sequence ordering.
Note
This method is called after refresh_observation, so that the internal buffer ‘observation’ is up-to-date.
See also
See InterfaceJiminyEnv.has_terminated documentation for details.
- compute_command(action, command)[source]¶
Compute the motors efforts to apply on the robot.
It simply forwards the command computed by the wrapped environment without any processing.
- Parameters:
action (ActT) – High-level target to achieve by means of the command.
command (ndarray) – Lower-level command to updated in-place.
- Return type:
None
- compute_reward(terminated, info)[source]¶
Compute the total reward, ie the sum of the original reward from the wrapped environment with the ad-hoc reward components that has been plugged on top of it.
See also
See InterfaceController.compute_reward documentation for details.
- Parameters:
- Returns:
Aggregated reward for the current step.
- Return type:
- class gym_jiminy.common.bases.pipeline.ObservedJiminyEnv(env, observer, **kwargs)[source]¶
Bases:
BasePipelineWrapper
[NestedObsT
,ActT
,BaseObsT
,ActT
],Generic
[NestedObsT
,ActT
,BaseObsT
]Wrap a BaseJiminyEnv Gym environment and a single observer.
The input ‘mes_1’ of the ‘observer_1’ must be consistent with the observation ‘obs_1’ of the environment. The observation space of the resulting unified environment will be the observation space of the highest-level observer, while its action space will be the one of the unwrapped environment ‘env’.
Note
The observation space gathers the original observation of the environment with the high-level features computed by the observer in gym.spaces.Dict instance. If the original observation is already a gym.spaces.Dict instance, then the features computed by the observer are added to if under (nested) key [‘features’, observer.name] along with its internal state [‘states’, observer.name] if any. Otherwise, the original observation is stored under key ‘measurement’.
Note
The environment and the observers all have their own update period.
Warning
This design is not suitable for learning the observer, but rather for robotic-oriented observers, such as sensor fusion algorithms, Kalman filters… It is recommended to add the observer into the policy itself if it has to be trainable.
- Parameters:
env (InterfaceJiminyEnv[BaseObsT, ActT]) – Environment to control. It can be an already controlled environment wrapped in ObservedJiminyEnv if one desires to stack several controllers with BaseJiminyEnv.
observer (BaseObserverBlock[OtherObsT, OtherStateT, BaseObsT, ActT]) – Observer to use to extract higher-level features.
kwargs (Any) – Extra keyword arguments to allow automatic pipeline wrapper generation.
- refresh_observation(measurement)[source]¶
Compute high-level features based on the current wrapped environment’s observation.
It gathers the original observation from the environment with the features computed by the observer.
Note
Internally, it can deal with multiple observers with different update periods. Besides, it is safe to call this method multiple times successively.
- Parameters:
measurement (EngineObsType) – Low-level measure from the environment to process to get higher-level observation.
- Return type:
None
- compute_command(action, command)[source]¶
Compute the motors efforts to apply on the robot.
It simply forwards the command computed by the wrapped environment without any processing.
- Parameters:
action (ActT) – High-level target to achieve by means of the command.
command (ndarray) – Lower-level command to updated in-place.
- Return type:
None
- class gym_jiminy.common.bases.pipeline.ControlledJiminyEnv(env, controller, augment_observation=False, **kwargs)[source]¶
Bases:
BasePipelineWrapper
[NestedObsT
,ActT
,BaseObsT
,BaseActT
],Generic
[NestedObsT
,ActT
,BaseObsT
,BaseActT
]Wrap a BaseJiminyEnv Gym environment and a single controller.
The output command ‘cmd_X’ of ‘ctrl_X’ must be consistent with the action space ‘act_X’ of the subsequent block. The action space of the resulting unified environment will be the action space of the highest-level controller ‘act_N’, while its observation space will be the one of the unwrapped environment ‘obs’. Alternatively, the later can also gather the (stacked) action space of the successive controllers if one is to observe the intermediary controllers’ targets.
Note
The environment and the controllers all have their own update period.
Warning
This design is not suitable for learning the controllers ‘ctrl_X’, but rather for robotic-oriented pre-defined and possibly model-based controllers, such as PID control, inverse kinematics, admittance control, or Model Predictive Control (MPC). It is recommended to add the controllers into the policy itself if it has to be trainable.
Note
As a reminder, env.step_dt refers to the learning step period, namely the timestep between two successive frames:
[observation, reward, terminated, truncated, info]
This definition remains true, independently of whether the environment is wrapped with a controller using this class. On the contrary, env.control_dt corresponds to the apparent control update period, namely the update period of the higher-level controller if multiple are piped together. The same goes for env.observe_dt.
- Parameters:
env (InterfaceJiminyEnv[BaseObsT, BaseActT]) – Environment to control. It can be an already controlled environment wrapped in ControlledJiminyEnv if one desires to stack several controllers with BaseJiminyEnv.
controller (BaseControllerBlock[ActT, OtherStateT, BaseObsT, BaseActT]) – Controller to use to send targets to the subsequent block.
augment_observation (bool) – Whether to gather the target state of the controller with the observation of the environment. Regardless, the internal state of the controller will be added if any. Optional: Disabled by default.
kwargs (Any) – Extra keyword arguments to allow automatic pipeline wrapper generation.
- refresh_observation(measurement)[source]¶
Compute the unified observation based on the current wrapped environment’s observation and controller’s target.
It gathers the actual observation from the environment with the target of the controller, if requested, otherwise it forwards the observation directly without any further processing.
Warning
Beware it shares the environment observation whenever possible for the sake of efficiency. Despite that, it is safe to call this method multiple times successively.
- Parameters:
measurement (EngineObsType) – Low-level measure from the environment to process to get higher-level observation.
- Return type:
None
- compute_command(action, command)[source]¶
Compute the motors efforts to apply on the robot.
In practice, it updates whenever necessary:
the target sent to the subsequent block by the controller
the command send to the robot by the environment through the subsequent block
- Parameters:
action (ActT) – High-level target to achieve by means of the command.
command (ndarray) – Lower-level command to update in-place.
- Return type:
None
- compute_reward(terminated, info)[source]¶
Compute the reward related to a specific control block, plus extra information that may be helpful for monitoring or debugging purposes.
For the corresponding MDP to be stationary, the computation of the reward is supposed to involve only the transition from previous to current state of the simulation (possibly comprising multiple agents) under the ongoing action.
By default, it returns 0.0 without extra information no matter what. The user is expected to provide an appropriate reward on its own, either by overloading this method or by wrapping the environment with ComposedJiminyEnv for modular environment pipeline design.
- Parameters:
- Returns:
Aggregated reward for the current step.
- Return type:
- class gym_jiminy.common.bases.pipeline.BaseTransformObservation(env)[source]¶
Bases:
BasePipelineWrapper
[TransformedObsT
,ActT
,ObsT
,ActT
],Generic
[TransformedObsT
,ObsT
,ActT
]Apply some transform on the observation of the wrapped environment.
The observation transform is only applied once per step, as post-processing right before returning. It is meant to change the way a whole pipeline environment is exposed to the outside rather than changing its internal machinery. Incidentally, the transformed observation is not to be involved in the computations of any subsequent pipeline layer.
Note
The user is expected to define the observation transform and its corresponding space by overloading both _initialize_action_space and transform_action. The transform will be applied at the end of every environment step.
Note
This wrapper derives from BasePipelineWrapper, and such as, it is considered internal unlike gym.Wrapper. This means that it will be taken into account when calling evaluate or play_interactive on the wrapped environment.
- Parameters:
env (InterfaceJiminyEnv[ObsT, ActT]) – Base or already wrapped jiminy environment.
kwargs – Extra keyword arguments for multiple inheritance.
- compute_command(action, command)[source]¶
Compute the motors efforts to apply on the robot.
It simply forwards the command computed by the wrapped environment without any processing.
- Parameters:
action (ActT) – High-level target to achieve by means of the command.
command (ndarray) – Lower-level command to update in-place.
- Return type:
None
- refresh_observation(measurement)[source]¶
Compute high-level features based on the current wrapped environment’s observation.
It calls transform_observation at step_dt update period, right after having refreshed the base observation.
Warning
The method transform_observation must have been overwritten by the user prior to calling this method.
- Parameters:
measurement (EngineObsType) – Low-level measure from the environment to process to get higher-level observation.
- Return type:
None
- abstract transform_observation()[source]¶
Compute the transformed observation from the original wrapped environment observation.
Note
The environment observation self.env.observation has been updated prior to calling this method and therefore can be safely accessed.
Note
For the sake of efficiency, this method should directly update in-place the pre-allocated transformed observation buffer self.observation instead of returning a temporary.
- Return type:
None
- class gym_jiminy.common.bases.pipeline.BaseTransformAction(env)[source]¶
Bases:
BasePipelineWrapper
[ObsT
,TransformedActT
,ObsT
,ActT
],Generic
[TransformedActT
,ObsT
,ActT
]Apply some transform on the action of the wrapped environment.
The action transform is only applied once per step, as pre-processing right at the beginning. It is meant to change the way a whole pipeline environment is exposed to the outside rather than changing its internal machinery.
Note
The user is expected to define the observation transform and its corresponding space by overloading both _initialize_action_space and transform_action. The transform will be applied at the beginning of every environment step.
Note
This wrapper derives from BasePipelineWrapper, and such as, it is considered internal unlike gym.Wrapper. This means that it will be taken into account when calling evaluate or play_interactive on the wrapped environment.
- Parameters:
env (InterfaceJiminyEnv[ObsT, ActT]) – Base or already wrapped jiminy environment.
kwargs – Extra keyword arguments for multiple inheritance.
- refresh_observation(measurement)[source]¶
Compute high-level features based on the current wrapped environment’s observation.
It simply forwards the observation computed by the wrapped environment without any processing.
- Parameters:
measurement (EngineObsType) – Low-level measure from the environment to process to get higher-level observation.
- Return type:
None
- compute_command(action, command)[source]¶
Compute the motors efforts to apply on the robot.
It calls transform_action at step_dt update period, which will update the environment action. Then, it delegates computation of the command to the base environment.
Warning
The method transform_action must have been overwritten by the user prior to calling this method.
- Parameters:
action (TransformedActT) – High-level target to achieve by means of the command.
command (ndarray) – Lower-level command to update in-place.
- Return type:
None
- abstract transform_action(action)[source]¶
Compute the transformed action from the provided wrapped environment action.
Note
For the sake of efficiency, this method should directly update in-place the pre-allocated action buffer of the wrapped environment self.env.action instead of returning a temporary.
- Parameters:
action (TransformedActT)
- Return type:
None