Quantities¶
This module promotes quantities as first-class objects.
Defining quantities this way allows for standardization of common intermediary metrics for computation of reward components and and termination conditions, eg the center of pressure or the average spatial velocity of a frame. Overall, it greatly reduces code duplication and bugs.
Apart from that, it offers a dedicated quantity manager that is responsible for optimizing the computation path, which is expected to significantly increase the step collection throughput. This speedup is achieved by caching already computed that did not changed since then, computing redundant intermediary quantities only once per step, and gathering similar quantities in a large batch to leverage vectorization of math instructions.
- class gym_jiminy.common.bases.quantities.WeakMutableCollection(callback=None)[source]¶
Bases:
MutableSet
,Generic
[ValueT
]Mutable unordered list container storing weak reference to objects. Elements will be discarded when no strong reference to the value exists anymore, and a user-specified callback will be triggered if any.
Internally, it is implemented as a set for which uniqueness is characterized by identity instead of equality operator.
- Parameters:
callback (Callable[[WeakMutableCollection[ValueT], ReferenceType], None] | None) – Callback that will be triggered every time an element is discarded from the container. Optional: None by default.
- class gym_jiminy.common.bases.quantities.QuantityStateMachine(value)[source]¶
Bases:
IntEnum
Specify the current state of a given (unique) quantity, which determines the steps to perform for retrieving its current value.
- IS_RESET = 0¶
The quantity at hands has just been reset. The quantity must first be initialized, then refreshed and finally stored in cached before to retrieve its value.
- IS_INITIALIZED = 1¶
The quantity at hands has been initialized but never evaluated for the current robot state. Its value must still be refreshed and stored in cache before to retrieve it.
- IS_CACHED = 2¶
The quantity at hands has been evaluated and its value stored in cache. As such, its value can be retrieve from cache directly.
Bases:
Generic
[ValueT
]Basic thread local shared cache.
Its API mimics std::optional from the Standard C++ library. All it does is encapsulating any Python object as a mutable variable, plus exposing a simple mechanism for keeping track of all “owners” of the cache.
Warning
This implementation is not thread safe.
Owners of the shared buffer, ie quantities relying on it to store the result of their evaluation. This information may be useful for determining the most efficient computation path overall.
Note
Quantities must add themselves to this list when passing them a shared cache instance.
Note
Internally, it stores weak references to avoid holding alive quantities that could be garbage collected otherwise. WeakSet cannot be used because owners are objects all having the same hash, eg “identical” quantities.
Add a given quantity instance to the set of co-owners associated with the shared cache at hands.
Warning
All shared cache co-owners must be instances of the same unique quantity. An exception will be thrown if an attempt is made to add a quantity instance that does not satisfy this condition.
- Parameters:
owner (InterfaceQuantity[ValueT]) – Quantity instance to add to the set of co-owners.
- Return type:
None
Remove a given quantity instance from the set of co-owners associated with the shared cache at hands.
- Parameters:
owner (InterfaceQuantity[ValueT]) – Quantity instance to remove from the set of co-owners.
- Return type:
None
Clear value stored in cache if any.
- Parameters:
ignore_auto_refresh (bool) – Whether to skip automatic refresh of all co-owner quantities of this shared cache. Optional: False by default.
reset_state_machine (bool) – Whether to reset completely the state machine of the underlying quantity, ie not considering it initialized anymore. Optional: False by default.
- Return type:
None
Return cached value if any, otherwise evaluate it and store it.
- Return type:
ValueT
- class gym_jiminy.common.bases.quantities.InterfaceQuantity(env, parent, requirements, *, auto_refresh=False)[source]¶
-
Interface for generic quantities involved observer-controller blocks, reward components or termination conditions.
Note
Quantities are meant to be managed automatically via QuantityManager. Dealing with quantities manually is error-prone, and as such, is strongly discourage. Nonetheless, power-user that understand the risks are allowed to do it.
Warning
Mutual dependency between quantities is disallowed.
Warning
The user is responsible for implementing the dunder methods __eq__ and __hash__ that characterize identical quantities. This property is used internally by QuantityManager to synchronize cache between them. It is advised to use decorator @dataclass(unsafe_hash=True) for convenience, but it can also be done manually.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
requirements (Dict[str, InterfaceQuantity]) – Intermediary quantities on which this quantity depends for its evaluation, as a dictionary whose keys are tuple gathering their respective class plus any keyword-arguments of its constructor except ‘env’ and ‘parent’.
auto_refresh (bool) – Whether this quantity must be refreshed automatically as soon as its shared cache has been cleared if specified, otherwise this does nothing.
- allow_update_graph: ClassVar[bool] = True¶
Whether dynamic computation graph update is allowed. This implies that the quantity can be reset at any point in time to re-compute the optimal computation path, typically after deletion or addition of some other node to its dependent sub-graph. When this happens, the quantity gets reset on the spot, even if a simulation is already running. This is not always acceptable, hence the capability to disable this feature at class-level.
- requirements: Dict[str, InterfaceQuantity]¶
Intermediary quantities on which this quantity may rely on for its evaluation at some point, depending on the optimal computation path at runtime. They will be exposed to the user as usual attributes.
- property cache: SharedCache[ValueT]¶
Get shared cache if available, otherwise raises an exception.
Warning
This method is not meant to be overloaded.
- is_active(any_cache_owner=False)[source]¶
Whether this quantity is considered active, namely initialize has been called at least once since previous tracking reset.
- get()[source]¶
Get cached value of requested quantity if available, otherwise evaluate it and store it in cache.
This quantity is considered active as soon as this method has been called at least once since previous tracking reset. The method is_active will be return true even before calling initialize.
Warning
This method is not meant to be overloaded.
- Return type:
ValueT
- reset(reset_tracking=False, *, ignore_other_instances=False)[source]¶
Consider that the quantity must be re-initialized before being evaluated once again.
If shared cache is available, then it will be cleared and all identity quantities will jointly be reset.
Note
This method must be called right before performing any agent step, otherwise this quantity will not be refreshed if it was evaluated previously.
Warning
This method is not meant to be overloaded.
- Parameters:
reset_tracking (bool) – Do not consider this quantity as active anymore until the get method gets called once again. Optional: False by default.
ignore_other_instances (bool) – Whether to skip reset of intermediary quantities as well as any shared cache co-owner quantity instances. Optional: False by default.
- Return type:
None
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- class gym_jiminy.common.bases.quantities.QuantityEvalMode(value)[source]¶
Bases:
IntEnum
Specify on which state to evaluate a given quantity.
- TRUE = 0¶
Current state of the environment.
- REFERENCE = 1¶
State of the reference trajectory at the current simulation time.
- class gym_jiminy.common.bases.quantities.AbstractQuantity(env, parent, requirements, *, mode=QuantityEvalMode.TRUE, auto_refresh=False)[source]¶
Bases:
InterfaceQuantity
,Generic
[ValueT
]Base class for generic quantities involved observer-controller blocks, reward components or termination conditions.
Note
A dataset of trajectories made available through self.trajectories. The latter is synchronized because all quantities as long as shared cached is available. At least one trajectory must be added to the dataset and selected prior to using QuantityEvalMode.REFERENCE evaluation mode since the dataset is initially empty by default.
See also
See InterfaceQuantity documentation for details.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
requirements (Dict[str, InterfaceQuantity]) – Intermediary quantities on which this quantity depends for its evaluation, as a dictionary whose keys are tuple gathering their respective class plus any keyword-arguments of its constructor except ‘env’ and ‘parent’.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. If mode is set to QuantityEvalMode.TRUE, then current simulation state will be used in dynamics computations. If mode is set to QuantityEvalMode.REFERENCE, then the state at the current simulation time of the selected reference trajectory will be used instead.
auto_refresh (bool) – Whether this quantity must be refreshed automatically as soon as its shared cache has been cleared if specified, otherwise this does nothing.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None
- gym_jiminy.common.bases.quantities.sync(fun)[source]¶
Wrap any InterfaceQuantity instance method to forward call to all co-owners of the same shared cache.
This wrapper is useful to keep all identical instances of the same quantity in sync.
- class gym_jiminy.common.bases.quantities.DatasetTrajectoryQuantity(env, parent)[source]¶
Bases:
InterfaceQuantity
[State
]This class manages a database of trajectories.
The database is empty by default. Trajectories must be added or discarded manually. Only one trajectory can be selected at once. Once a trajectory has been selecting, its state at the current simulation can be easily retrieved.
This class does not require to only adding trajectories for which all attributes of the underlying state sequence have been specified. Missing attributes of a trajectory will also be missing from the retrieved state. It is the responsible of the user to make sure all cases are properly handled if needed.
All instances of this quantity sharing the same cache are synchronized, which means that adding, discarding, or selecting a trajectory on any of them would propagate on all the others.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
- property trajectory: Trajectory¶
Trajectory that is currently selected if any, raises an exception otherwise.
- property use_theoretical_model: bool¶
Whether the selected trajectory is associated with the theoretical dynamical model or extended simulation model of the robot.
- add(name, trajectory)[source]¶
Jointly add a trajectory to the local internal registry of all instances sharing the same cache as this quantity.
- Parameters:
name (str) – Desired name of the trajectory. It must be unique. If a trajectory with the exact same name already exists, then it must be discarded first, so as to prevent silently overwriting it by mistake.
trajectory (Trajectory) – Trajectory instance to register.
- Return type:
None
- discard(name)[source]¶
Jointly remove a trajectory from the local internal registry of all instances sharing the same cache as this quantity.
- Parameters:
name (str) – Name of the trajectory to discard.
- Return type:
None
- select(name, mode='raise')[source]¶
Jointly select a trajectory in the internal registry of all instances sharing the same cache as this quantity.
- property cache: SharedCache[ValueT]¶
Get shared cache if available, otherwise raises an exception.
Warning
This method is not meant to be overloaded.
- class gym_jiminy.common.bases.quantities.StateQuantity(env, parent, *, mode=QuantityEvalMode.TRUE, update_kinematics=True, update_dynamics=False, update_centroidal=False, update_energy=False, update_jacobian=False)[source]¶
Bases:
InterfaceQuantity
[State
]State to consider when evaluating any quantity deriving from AbstractQuantity using the same evaluation mode as this instance.
This quantity is refreshed automatically no matter what. This guarantees that all low-level kinematics and dynamics quantities that can be computed from the current state are up-to-date. More specifically, every quantities would be up-to-date if the evaluation mode is QuantityEvalMode.TRUE, while it would depends on the information available on the selected trajectory if the evaluation mode is QuantityEvalMode.REFERENCE. See update_quantities documentation for details.
- Parameters:
env (InterfaceJiminyEnv) – Base or wrapped jiminy environment.
parent (InterfaceQuantity | None) – Higher-level quantity from which this quantity is a requirement if any, None otherwise.
mode (QuantityEvalMode) – Desired mode of evaluation for this quantity. If mode is set to QuantityEvalMode.TRUE, then current simulation state will be used in dynamics computations. If mode is set to QuantityEvalMode.REFERENCE, then at the state of some reference trajectory at the current simulation time will be used instead. Optional: ‘QuantityEvalMode.TRUE’ by default.
update_kinematics (bool) – Whether to update body and frame transforms, spatial velocities and accelerations stored in self.pinocchio_data if necessary to be consistent with the current state of the robot. This argument has no effect if mode is set to QuantityEvalMode.TRUE because this property is already guarantee. Optional: False by default.
update_dynamics (bool) – Whether to update the non-linear effects and the joint internal forces stored in self.pinocchio_data if necessary. Optional: False by default.
update_centroidal (bool) – Whether to update the centroidal dynamics (incl. CoM) stored in self.pinocchio_data if necessary. Optional: True by default.
update_energy (bool) – Whether to update the potential and kinematic energy stored in self.pinocchio_data if necessary. Optional: False by default.
update_jacobian (bool) – Whether to update the joint Jacobian matrices stored in self.pinocchio_data if necessary. Optional: False by default.
- mode: QuantityEvalMode¶
Specify on which state to evaluate this quantity. See QuantityEvalMode documentation for details about each mode.
Warning
Mode REFERENCE requires a reference trajectory to be selected manually prior to evaluating this quantity for the first time.
- initialize()[source]¶
Initialize internal buffers.
This is typically useful to refresh shared memory proxies or to re-initialize pre-allocated buffers.
Warning
Intermediary quantities ‘requirements’ are NOT initialized automatically because they can be initialized lazily in most cases, or are optional depending on the most efficient computation path at run-time. It is up to the developer implementing quantities to take care of it.
Note
This method must be called before starting a new episode.
Note
Lazy-initialization is used for efficiency, ie initialize will be called before the first time refresh has to be called, which may never be the case if cache is shared between multiple identical instances of the same quantity.
- Return type:
None