diff --git a/.github/workflows/linux.yml b/.github/workflows/linux.yml index 073c3272e..60b0cc968 100644 --- a/.github/workflows/linux.yml +++ b/.github/workflows/linux.yml @@ -140,15 +140,13 @@ jobs: if: matrix.BUILD_TYPE != 'Debug' && matrix.PYTHON_VERSION == '3.10' run: | # Generate stubs - # FIXME: stubgen does not work with Numpy 2.X + # FIXME: stubgen does not work with Numpy 2.X without option `--no-analysis` # (see https://github.com/python/mypy/issues/17396) - "${PYTHON_EXECUTABLE}" -m pip install "numpy<2.0" - stubgen -p jiminy_py -o ${RootDir}/build/pypi/jiminy_py/src + stubgen -p jiminy_py -o ${RootDir}/build/pypi/jiminy_py/src --no-analysis "${PYTHON_EXECUTABLE}" "${RootDir}/build_tools/stubgen.py" \ -o ${RootDir}/build/stubs --ignore-invalid=all jiminy_py cp ${RootDir}/build/stubs/jiminy_py-stubs/core/__init__.pyi \ ${RootDir}/build/pypi/jiminy_py/src/jiminy_py/core/core.pyi - "${PYTHON_EXECUTABLE}" -m pip install --upgrade "numpy>=1.24" numba torch # Re-install jiminy with stubs cd "${RootDir}/build" diff --git a/.github/workflows/macos.yml b/.github/workflows/macos.yml index 49feb7d0a..71afcf1e8 100644 --- a/.github/workflows/macos.yml +++ b/.github/workflows/macos.yml @@ -142,10 +142,9 @@ jobs: # Generate stubs if [[ "${{ matrix.BUILD_TYPE }}" != 'Debug' && "${{ matrix.OS }}" != 'macos-13' ]] ; then - # FIXME: stubgen does not work with Numpy 2.X + # FIXME: stubgen does not work with Numpy 2.X without option `--no-analysis` # (see https://github.com/python/mypy/issues/17396) - "${PYTHON_EXECUTABLE}" -m pip install "numpy<2.0" - stubgen -p jiminy_py -o ${RootDir}/build/pypi/jiminy_py/src + stubgen -p jiminy_py -o ${RootDir}/build/pypi/jiminy_py/src --no-analysis # FIXME: Python 3.10 and Python 3.11 crashes when generating stubs without any backtrace... if [[ "${{ matrix.PYTHON_VERSION }}" != '3.10' && "${{ matrix.PYTHON_VERSION }}" != '3.11' ]] ; then # lldb --batch -o "settings set target.process.stop-on-exec false" \ @@ -155,7 +154,6 @@ jobs: cp ${RootDir}/build/stubs/jiminy_py-stubs/core/__init__.pyi \ ${RootDir}/build/pypi/jiminy_py/src/jiminy_py/core/core.pyi fi - "${PYTHON_EXECUTABLE}" -m pip install --upgrade "numpy>=1.24" numba torch fi # Generate wheels diff --git a/.github/workflows/manylinux.yml b/.github/workflows/manylinux.yml index 6a5912a3d..7a5942ef7 100644 --- a/.github/workflows/manylinux.yml +++ b/.github/workflows/manylinux.yml @@ -112,15 +112,13 @@ jobs: export LD_LIBRARY_PATH="$InstallDir/lib:$InstallDir/lib64:/usr/local/lib" # Generate stubs - # FIXME: stubgen does not work with Numpy 2.X + # FIXME: stubgen does not work with Numpy 2.X without option `--no-analysis` # (see https://github.com/python/mypy/issues/17396) - "${PYTHON_EXECUTABLE}" -m pip install "numpy<2.0" - stubgen -p jiminy_py -o $RootDir/build/pypi/jiminy_py/src + stubgen -p jiminy_py -o $RootDir/build/pypi/jiminy_py/src --no-analysis "${PYTHON_EXECUTABLE}" "$RootDir/build_tools/stubgen.py" \ -o $RootDir/build/stubs --ignore-invalid=all jiminy_py \cp $RootDir/build/stubs/jiminy_py-stubs/core/__init__.pyi \ $RootDir/build/pypi/jiminy_py/src/jiminy_py/core/core.pyi - "${PYTHON_EXECUTABLE}" -m pip install --upgrade "numpy>=1.24" numba # Generate wheels cd "$RootDir/build" diff --git a/.github/workflows/win.yml b/.github/workflows/win.yml index 30f1afcf9..6eb4b9e24 100644 --- a/.github/workflows/win.yml +++ b/.github/workflows/win.yml @@ -123,17 +123,13 @@ jobs: ${env:Path} += ";$InstallDir/lib" # Generate stubs - if ("${{ matrix.PYTHON_VERSION }}" -ne "3.13") { - # FIXME: stubgen does not work with Numpy 2.X - # (see https://github.com/python/mypy/issues/17396) - python -m pip install "numpy<2.0" - stubgen -p jiminy_py -o $RootDir/build/pypi/jiminy_py/src - python "$RootDir/build_tools/stubgen.py" ` - -o $RootDir/build/stubs --ignore-invalid=all jiminy_py - Copy-Item -Force -Path "$RootDir/build/stubs/jiminy_py-stubs/core/__init__.pyi" ` - -Destination "$RootDir/build/pypi/jiminy_py/src/jiminy_py/core/core.pyi" - python -m pip install --upgrade "numpy>=1.24" numba torch - } + # FIXME: stubgen does not work with Numpy 2.X without option `--no-analysis` + # (see https://github.com/python/mypy/issues/17396) + stubgen -p jiminy_py -o $RootDir/build/pypi/jiminy_py/src --no-analysis + python "$RootDir/build_tools/stubgen.py" ` + -o $RootDir/build/stubs --ignore-invalid=all jiminy_py + Copy-Item -Force -Path "$RootDir/build/stubs/jiminy_py-stubs/core/__init__.pyi" ` + -Destination "$RootDir/build/pypi/jiminy_py/src/jiminy_py/core/core.pyi" # Generate wheels Set-Location -Path "$RootDir/build" diff --git a/python/gym_jiminy/common/gym_jiminy/common/bases/__init__.py b/python/gym_jiminy/common/gym_jiminy/common/bases/__init__.py index c4661d4ca..7164d1c74 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/bases/__init__.py +++ b/python/gym_jiminy/common/gym_jiminy/common/bases/__init__.py @@ -24,7 +24,8 @@ MixtureReward, AbstractTerminationCondition, QuantityTermination, - EpisodeState) + EpisodeState, + partial_hashable) from .blocks import (BlockState, InterfaceBlock, BaseObserverBlock, @@ -74,5 +75,6 @@ 'QuantityCreator', 'EpisodeState', 'StateQuantity', - 'DatasetTrajectoryQuantity' + 'DatasetTrajectoryQuantity', + 'partial_hashable' ] diff --git a/python/gym_jiminy/common/gym_jiminy/common/bases/compositions.py b/python/gym_jiminy/common/gym_jiminy/common/bases/compositions.py index 6a76307c0..35e19b90a 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/bases/compositions.py +++ b/python/gym_jiminy/common/gym_jiminy/common/bases/compositions.py @@ -6,9 +6,13 @@ This modular approach allows for standardization of usual metrics. Overall, it greatly reduces code duplication and bugs. """ +import inspect +from functools import partial from abc import abstractmethod, ABCMeta from enum import IntEnum -from typing import Tuple, Sequence, Callable, Union, Optional, Generic, TypeVar +from typing import ( + Tuple, Sequence, Callable, Union, Optional, Generic, Any, TypeVar, + TYPE_CHECKING) import numpy as np @@ -25,6 +29,53 @@ ArrayLikeOrScalar = Union[ArrayOrScalar, Sequence[Union[Number, np.number]]] +class partial_hashable(partial): # pylint: disable=invalid-name + """Extends standard `functools.Partial` class with hash and equality + operator. + + Two partial instances are equal if they are wrapping the exact same + function (i.e. pointing to the same memory address as per `id` build-in + function), and bindings the same arguments (i.e. all arguments are equal + as per `==` operator). Note that it does not matter if the constructor + arguments of `Partial` itself are positional or keyword-based. Internally, + they will be stored in an ordered list of keyword-only arguments for + equality check. + + .. warning:: + Try to instantiate this class with invalid arguments for the method + being wrapped (e.g. specifying multiple values for the same argument) + would raise a `TypeError` exception, unlike `functools.partial` that + would only fail when calling the resulting callable object. + """ + + if TYPE_CHECKING: + _normalized_args: Tuple[Any, ...] + + def __new__(cls, + func: Callable, /, + *args: Any, + **kwargs: Any) -> "partial_hashable": + # Call base implementation + self = super(partial_hashable, cls).__new__(cls, func, *args, **kwargs) + + # Pre-compute normalized arguments once and for all + sig = inspect.signature(self.func) + bound = sig.bind_partial(*self.args, **(self.keywords or {})) + bound.apply_defaults() + self._normalized_args = tuple(bound.arguments.values()) + + return self + + def __eq__(self, other: Any) -> bool: + if not isinstance(other, partial_hashable): + return False + return self.func == other.func and ( + self._normalized_args == other._normalized_args) + + def __hash__(self) -> int: + return hash((self.func, self._normalized_args)) + + class AbstractReward(metaclass=ABCMeta): """Abstract class from which all reward component must derived. @@ -514,7 +565,7 @@ def __call__(self, info: InfoType) -> Tuple[bool, bool]: return is_terminated, is_truncated -class QuantityTermination(AbstractTerminationCondition, Generic[ValueT]): +class QuantityTermination(AbstractTerminationCondition): """Convenience class making it easy to derive termination conditions from generic quantities. diff --git a/python/gym_jiminy/common/gym_jiminy/common/compositions/__init__.py b/python/gym_jiminy/common/gym_jiminy/common/compositions/__init__.py index cf0778b92..3ec6538d6 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/compositions/__init__.py +++ b/python/gym_jiminy/common/gym_jiminy/common/compositions/__init__.py @@ -7,6 +7,7 @@ from .generic import (SurviveReward, TrackingQuantityReward, TrackingActuatedJointPositionsReward, + MinimizeMechanicalPowerConsumption, DriftTrackingQuantityTermination, ShiftTrackingQuantityTermination, MechanicalSafetyTermination, @@ -38,6 +39,7 @@ "SurviveReward", "MinimizeFrictionReward", "MinimizeAngularMomentumReward", + "MinimizeMechanicalPowerConsumption", "TrackingQuantityReward", "TrackingActuatedJointPositionsReward", "TrackingBaseHeightReward", diff --git a/python/gym_jiminy/common/gym_jiminy/common/compositions/generic.py b/python/gym_jiminy/common/gym_jiminy/common/compositions/generic.py index 4d9db1389..5353b91c8 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/compositions/generic.py +++ b/python/gym_jiminy/common/gym_jiminy/common/compositions/generic.py @@ -14,8 +14,8 @@ from ..bases import ( InfoType, QuantityCreator, InterfaceJiminyEnv, InterfaceQuantity, QuantityEvalMode, AbstractReward, QuantityReward, - AbstractTerminationCondition, QuantityTermination) -from ..bases.compositions import ArrayOrScalar, ArrayLikeOrScalar, Number + AbstractTerminationCondition, QuantityTermination, partial_hashable) +from ..bases.compositions import ArrayOrScalar, Number from ..quantities import ( EnergyGenerationMode, StackedQuantity, UnaryOpQuantity, BinaryOpQuantity, MultiActuatedJointKinematic, MechanicalPowerConsumption, @@ -150,34 +150,96 @@ def __init__(self, cutoff) -class DriftTrackingQuantityTermination(QuantityTermination): - """Base class to derive termination condition from the difference between - the current and reference drift of a given quantity. +class MinimizeMechanicalPowerConsumption(QuantityReward): + """Encourages the agent to minimize its average mechanical power + consumption. - The drift is defined as the difference between the most recent and oldest - values of a time series. In this case, a variable-length horizon bounded by - 'max_stack' is considered. + This reward is useful to favor carefully tailored short burst of motion + that may be power-angry for a very short duration, but more energy + efficient on average. The resulting motion tends to be more human-like. + """ + def __init__( + self, + env: InterfaceJiminyEnv, + cutoff: float, + *, + horizon: float, + generator_mode: EnergyGenerationMode = EnergyGenerationMode.CHARGE + ) -> None: + """ + :param env: Base or wrapped jiminy environment. + :param cutoff: Cutoff threshold for the RBF kernel transform. + :param horizon: Horizon over which values of the quantity will be + stacked before computing the average. + :param generator_mode: Specify what happens to the energy generated by + motors when breaking. + Optional: `EnergyGenerationMode.CHARGE` by + default. + """ + # Backup some user argument(s) + self.cutoff = cutoff - All elements must be within bounds for at least one time step in the fixed - horizon. If so, then the episode continues, otherwise it is either - truncated or terminated according to 'is_truncation' constructor argument. - This only applies after the end of a grace period. Before that, the episode - continues no matter what. + # Call base implementation + super().__init__( + env, + "reward_power_consumption", + (AverageMechanicalPowerConsumption, dict( + horizon=horizon, + generator_mode=generator_mode)), + partial(radial_basis_function, cutoff=self.cutoff, order=2), + is_normalized=True, + is_terminal=False) + + +@nb.jit(nopython=True, cache=True, fastmath=True, inline='always') +def compute_drift_error(delta_true: np.ndarray, + delta_ref: np.ndarray) -> float: + """Compute the difference between the true and reference variation of a + quantity over a given horizon, then apply some post-processing on it if + requested. + + :param delta_true: True value of the variation as a N-dimensional array. + :param delta_ref: Reference value of the variation as a N-dimensional + array. + """ + drift = delta_true - delta_ref + if isinstance(drift, float): + return abs(drift) + return np.linalg.norm(drift.reshape((-1,))) # type: ignore[return-value] + + +class DriftTrackingQuantityTermination(QuantityTermination): + """Base class to derive termination condition from the drift between the + current and reference values of a given quantity over a horizon. + + The drift is defined as the difference between the current and reference + variation of the quantity over a variable-length horizon bounded by + 'max_stack'. This variation is computed from the whole history of values + corresponding to this horizon, which is basically a sliding window. For + Euclidean spaces, this variation is simply computed as the difference + between most recent and oldest values stored in the history. + + In practice, no bound check is applied on the drift directly, which may be + multi-variate at this point. Instead, the L2-norm is used as metric in the + variation space for computing the error between the current and reference + variation of the quantity. + + If the error does not exceed the maximum threshold, then the episode + continues. Otherwise, it is either truncated or terminated according to + 'is_truncation' constructor argument. This check only applies after the end + of a grace period. Before that, the episode continues no matter what. """ def __init__(self, env: InterfaceJiminyEnv, name: str, quantity_creator: Callable[ [QuantityEvalMode], QuantityCreator[ArrayOrScalar]], - low: Optional[ArrayLikeOrScalar], - high: Optional[ArrayLikeOrScalar], + thr: float, horizon: float, grace_period: float = 0.0, *, op: Callable[[ArrayLike, ArrayLike], ArrayOrScalar] = sub, bounds_only: bool = True, - post_fn: Optional[Callable[ - [ArrayOrScalar], ArrayOrScalar]] = None, is_truncation: bool = False, training_only: bool = False) -> None: """ @@ -194,8 +256,8 @@ def __init__(self, reward after some post-processing, plus any keyword-arguments of its constructor except 'env' and 'parent'. - :param low: Lower bound below which termination is triggered. - :param high: Upper bound above which termination is triggered. + :param thr: Termination is triggered if the drift exceeds this + threshold. :param horizon: Horizon over which values of the quantity will be stacked before computing the drift. :param grace_period: Grace period effective only at the very beginning @@ -212,17 +274,11 @@ def __init__(self, history is is appropriate for position in Euclidean space, but not for orientation as it is important to count turns. Optional: `sub` by default. - :param bounds_only: Whether to pass only the ecent and oldest value + :param bounds_only: Whether to pass only the recent and oldest value stored in the history as input argument of `op` instead of the complete history (stacked as last dimenstion). Optional: True by default. - :apram post_fn: Optional callable taking the drift between the true and - reference varation of the quantity over the whole - history as input argument, and returning some - post-processed value to which bound checking will be - applied. `None` to skip post-processing entirely. - Optional: None by default. :param is_truncation: Whether the episode should be considered terminated or truncated whenever the termination condition is triggered. @@ -240,7 +296,6 @@ def __init__(self, # Backup user argument(s) self.max_stack = max_stack self.op = op - self.post_fn = post_fn self.bounds_only = bounds_only # Define drift of quantity @@ -270,34 +325,58 @@ def __init__(self, drift_tracking_quantity = (BinaryOpQuantity, dict( quantity_left=delta_creator(QuantityEvalMode.TRUE), quantity_right=delta_creator(QuantityEvalMode.REFERENCE), - op=self._compute_drift_error)) + op=compute_drift_error)) # Call base implementation super().__init__(env, name, drift_tracking_quantity, # type: ignore[arg-type] - low, - high, + None, + np.array(thr), grace_period, is_truncation=is_truncation, training_only=training_only) - def _compute_drift_error(self, - left: np.ndarray, - right: np.ndarray) -> ArrayOrScalar: - """Compute the difference between the true and reference drift over - a given horizon, then apply some post-processing on it if requested. - :param left: True value of the drift as a N-dimensional array. - :param right: Reference value of the drift as a N-dimensional array. - """ - diff = left - right - if self.post_fn is not None: - return self.post_fn(diff) - return diff +@nb.jit(nopython=True, cache=True, fastmath=True) +def min_norm(values: np.ndarray) -> float: + """Compute the minimum Euclidean norm over all timestamps of a multivariate + time series. + + :param values: Time series as a N-dimensional array whose last dimension + corresponds to individual timestamps over a finite horizon. + The value at each timestamp will be regarded as a 1D vector + for computing their Euclidean norm. + """ + num_times = values.shape[-1] + values_squared_flat = np.square(values).reshape((-1, num_times)) + return np.sqrt(np.min(np.sum(values_squared_flat, axis=0))) + + +def compute_min_distance(op: Callable[[np.ndarray, np.ndarray], np.ndarray], + left: np.ndarray, + right: np.ndarray) -> float: + """Compute the minimum time-aligned Euclidean distance between two + multivariate time series kept in sync. + + Internally, the time-aligned difference between the two time series will + first be computed according to the user-specified binary operator 'op'. The + classical Euclidean norm of the difference is then computed over all + timestamps individually and the minimum value is returned. + + :param left: Time series as a N-dimensional array whose first dimension + corresponds to individual timestamps over a finite horizon. + The value at each timestamp will be regarded as a 1D vector + for computing their Euclidean norm. It will be passed as + left-hand side of the binary operator 'op'. + :param right: Time series as a N-dimensional array with the exact same + shape as 'left'. See 'left' for details. It will be passed as + right-hand side of the binary operator 'op'. + """ + return min_norm(op(left, right)) -class ShiftTrackingQuantityTermination(QuantityTermination[np.ndarray]): +class ShiftTrackingQuantityTermination(QuantityTermination): """Base class to derive termination condition from the shift between the current and reference values of a given quantity. @@ -372,24 +451,6 @@ def __init__(self, self.max_stack = max_stack self.op = op - # Jit-able method computing minimum distance between two time series - @nb.jit(nopython=True, cache=True) - def min_norm(values: np.ndarray) -> float: - """Compute the minimum Euclidean norm over all timestamps of a - multivariate time series. - - :param values: Time series as a N-dimensional array whose last - dimension corresponds to individual timestamps over - a finite horizon. The value at each timestamp will - be regarded as a 1D vector for computing their - Euclidean norm. - """ - num_times = values.shape[-1] - values_squared_flat = np.square(values).reshape((-1, num_times)) - return np.sqrt(np.min(np.sum(values_squared_flat, axis=0))) - - self._min_norm = min_norm - # Define drift of quantity stack_creator = lambda mode: (StackedQuantity, dict( # noqa: E731 quantity=quantity_creator(mode), @@ -401,7 +462,7 @@ def min_norm(values: np.ndarray) -> float: shift_tracking_quantity = (BinaryOpQuantity, dict( quantity_left=stack_creator(QuantityEvalMode.TRUE), quantity_right=stack_creator(QuantityEvalMode.REFERENCE), - op=self._compute_min_distance)) + op=partial_hashable(compute_min_distance, op))) # Call base implementation super().__init__(env, @@ -413,28 +474,6 @@ def min_norm(values: np.ndarray) -> float: is_truncation=is_truncation, training_only=training_only) - def _compute_min_distance(self, - left: np.ndarray, - right: np.ndarray) -> float: - """Compute the minimum time-aligned Euclidean distance between two - multivariate time series kept in sync. - - Internally, the time-aligned difference between the two time series - will first be computed according to the user-specified binary operator - 'op'. The classical Euclidean norm of the difference is then computed - over all timestamps individually and the minimum value is returned. - - :param left: Time series as a N-dimensional array whose first dimension - corresponds to individual timestamps over a finite - horizon. The value at each timestamp will be regarded as a - 1D vector for computing their Euclidean norm. It will be - passed as left-hand side of the binary operator 'op'. - :param right: Time series as a N-dimensional array with the exact same - shape as 'left'. See 'left' for details. It will be - passed as right-hand side of the binary operator 'op'. - """ - return self._min_norm(self.op(left, right)) - @dataclass(unsafe_hash=True) class _MultiActuatedJointBoundDistance( @@ -623,12 +662,12 @@ def __init__( # Pick the right quantity creator depending on the horizon quantity_creator: QuantityCreator if horizon is None: - quantity_creator = (AverageMechanicalPowerConsumption, dict( - horizon=self.horizon, + quantity_creator = (MechanicalPowerConsumption, dict( generator_mode=self.generator_mode, mode=QuantityEvalMode.TRUE)) else: - quantity_creator = (MechanicalPowerConsumption, dict( + quantity_creator = (AverageMechanicalPowerConsumption, dict( + horizon=self.horizon, generator_mode=self.generator_mode, mode=QuantityEvalMode.TRUE)) diff --git a/python/gym_jiminy/common/gym_jiminy/common/compositions/locomotion.py b/python/gym_jiminy/common/gym_jiminy/common/compositions/locomotion.py index b0cf6479f..7c07afd60 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/compositions/locomotion.py +++ b/python/gym_jiminy/common/gym_jiminy/common/compositions/locomotion.py @@ -403,6 +403,32 @@ def __init__(self, training_only=training_only) +@nb.jit(nopython=True, cache=True, fastmath=True) +def min_depth(positions: np.ndarray, + heights: np.ndarray, + normals: np.ndarray) -> float: + """Approximate minimum distance from the ground profile among a set of the + query points. + + Internally, it uses a first order approximation assuming zero local + curvature around each query point. + + :param positions: Position of all the query points from which to compute + from the ground profile, as a 2D array whose first + dimension gathers the 3 position coordinates (X, Y, Z) + while the second correponds to the N individual query + points. + :param heights: Vertical height wrt the ground profile of the N individual + query points in world frame as 1D array. + :param normals: Normal of the ground profile for the projection in world + plane of all the query points, as a 2D array whose first + dimension gathers the 3 position coordinates (X, Y, Z) + while the second correponds to the N individual query + points. + """ + return np.min((positions[2] - heights) * normals[2]) + + @dataclass(unsafe_hash=True) class _MultiContactMinGroundDistance(InterfaceQuantity[float]): """Minimum distance from the ground profile among all the contact points. @@ -440,34 +466,6 @@ def __init__(self, ))), auto_refresh=False) - # Jit-able method computing the minimum first-order depth - @nb.jit(nopython=True, cache=True, fastmath=True) - def min_depth(positions: np.ndarray, - heights: np.ndarray, - normals: np.ndarray) -> float: - """Approximate minimum distance from the ground profile among a set - of the query points. - - Internally, it uses a first order approximation assuming zero local - curvature around each query point. - - :param positions: Position of all the query points from which to - compute from the ground profile, as a 2D array - whose first dimension gathers the 3 position - coordinates (X, Y, Z) while the second correponds - to the N individual query points. - :param heights: Vertical height wrt the ground profile of the N - individual query points in world frame as 1D array. - :param normals: Normal of the ground profile for the projection in - world plane of all the query points, as a 2D array - whose first dimension gathers the 3 position - coordinates (X, Y, Z) while the second correponds - to the N individual query points. - """ - return np.min((positions[2] - heights) * normals[2]) - - self._min_depth = min_depth - # Reference to the heightmap function for the ongoing epsiode self._heightmap = jiminy.HeightmapFunction(lambda: None) @@ -496,7 +494,7 @@ def refresh(self) -> float: # self._normals /= np.linalg.norm(self._normals, axis=0) # First-order distance estimation assuming no curvature - return self._min_depth(positions, self._heights, self._normals) + return min_depth(positions, self._heights, self._normals) class FlyingTermination(QuantityTermination): @@ -579,16 +577,6 @@ def __init__(self, training_only=training_only) -@nb.jit(nopython=True, cache=True, fastmath=True, inline='always') -def l2_norm(array: np.ndarray) -> np.floating: - """Compute the L2-norm of a N-dimensional array as after flattening as a - vector. - - :param array: Input array. - """ - return np.linalg.norm(array.reshape((-1,))) - - class DriftTrackingBaseOdometryPositionTermination( DriftTrackingQuantityTermination): """Terminate the episode if the current base odometry position is drifting @@ -645,11 +633,9 @@ def __init__(self, mode=mode)), axis=0, keys=(0, 1))), - None, max_position_err, horizon, grace_period, - post_fn=l2_norm, is_truncation=False, training_only=training_only) @@ -721,6 +707,10 @@ class DriftTrackingBaseOdometryOrientationTermination( See `BaseOdometryPose` and `DriftTrackingBaseOdometryPositionTermination` documentations for details. + + .. note:: + It takes into account the number of turns of the yaw angle of the + floating base over the whole span of the history. """ def __init__(self, env: InterfaceJiminyEnv, @@ -754,13 +744,11 @@ def __init__(self, mode=mode)), axis=0, keys=(2,))), - -max_orientation_err, max_orientation_err, horizon, grace_period, op=angle_total, bounds_only=False, - # post_fn=angle_difference, is_truncation=False, training_only=training_only) @@ -786,7 +774,7 @@ def __init__(self, """ :param env: Base or wrapped jiminy environment. :param max_position_err: - Maximum drift error in translation (X, Y) in world plane above + Maximum shift error in translation (X, Y) in world plane above which termination is triggered. :param horizon: Horizon over which values of the quantity will be stacked before computing the shift. diff --git a/python/gym_jiminy/common/gym_jiminy/common/compositions/mixin.py b/python/gym_jiminy/common/gym_jiminy/common/compositions/mixin.py index 0cd17eec1..f1a3e11fe 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/compositions/mixin.py +++ b/python/gym_jiminy/common/gym_jiminy/common/compositions/mixin.py @@ -47,7 +47,7 @@ def radial_basis_function(error: ArrayOrScalar, :param cutoff: Cut-off threshold to consider. :param order: Order of L^p-norm that will be used as distance metric. """ - error_ = np.asarray(error) + error_ = np.atleast_1d(np.asarray(error)) is_contiguous = error_.flags.f_contiguous or error_.flags.c_contiguous if is_contiguous or order != 2: if error_.ndim > 1 and not is_contiguous: @@ -66,6 +66,45 @@ def radial_basis_function(error: ArrayOrScalar, return math.pow(CUTOFF_ESP, squared_dist_rel) +@nb.jit(nopython=True, cache=True, fastmath=True) +def weighted_norm(weights: Tuple[float, ...], + order: Union[int, float], + values: Tuple[Optional[float], ...] + ) -> Optional[float]: + """Compute the weighted L^p-norm of all the reward components that has been + evaluated, filtering out the others. + + This method returns `None` if no reward component has been evaluated. + + :param weights: Sequence of weights for each reward component, with same + ordering as 'components'. + :param order: Order of the L^p-norm. + :param values: Sequence of scalar value for reward components that has been + evaluated, `None` otherwise, with the same ordering as + 'components'. + + :returns: Scalar value if at least one of the reward component has been + evaluated, `None` otherwise. + """ + is_max_norm = order == float('inf') + total, any_value = 0.0, False + for value, weight in zip(values, weights): + if value is not None: + if is_max_norm: + if any_value: + total = max(total, weight * value) + else: + total = weight * value + else: + total += weight * math.pow(value, order) + any_value = True + if any_value: + if is_max_norm: + return total + return math.pow(total, 1.0 / order) + return None + + class AdditiveMixtureReward(MixtureReward): """Weighted L^p-norm of multiple independent reward components. @@ -142,46 +181,6 @@ def __init__(self, self.order = order self.weights = tuple(weights) - # Jit-able method computing the weighted sum of reward components - @nb.jit(nopython=True, cache=True, fastmath=True) - def weighted_norm(weights: Tuple[float, ...], - order: Union[int, float], - values: Tuple[Optional[float], ...] - ) -> Optional[float]: - """Compute the weighted L^p-norm of all the reward components that - has been evaluated, filtering out the others. - - This method returns `None` if no reward component has been - evaluated. - - :param weights: Sequence of weights for each reward component, with - same ordering as 'components'. - :param order: Order of the L^p-norm. - :param values: Sequence of scalar value for reward components that - has been evaluated, `None` otherwise, with the same - ordering as 'components'. - - :returns: Scalar value if at least one of the reward component has - been evaluated, `None` otherwise. - """ - is_max_norm = order == float('inf') - total, any_value = 0.0, False - for value, weight in zip(values, weights): - if value is not None: - if is_max_norm: - if any_value: - total = max(total, weight * value) - else: - total = weight * value - else: - total += weight * math.pow(value, order) - any_value = True - if any_value: - if is_max_norm: - return total - return math.pow(total, 1.0 / order) - return None - # Call base implementation super().__init__( env, @@ -200,6 +199,29 @@ def weighted_norm(weights: Tuple[float, ...], """ +@nb.jit(nopython=True, cache=True, fastmath=True) +def geometric_mean(values: Tuple[Optional[float], ...]) -> Optional[float]: + """Compute the product of all the reward components that has been + evaluated, filtering out the others. + + This method returns `None` if no reward component has been evaluated. + + :param values: Sequence of scalar value for reward components that has been + evaluated, `None` otherwise, with the same ordering as + 'components'. + + :returns: Scalar value if at least one of the reward component has been + evaluated, `None` otherwise. + """ + total, any_value, n_values = 1.0, False, 0 + for value in values: + if value is not None: + total *= value + any_value = True + n_values += 1 + return math.pow(total, 1.0 / n_values) if any_value else None + + class MultiplicativeMixtureReward(MixtureReward): """Geometric mean of independent reward components, to promote versatility. @@ -223,31 +245,6 @@ def __init__(self, # Determine whether the cumulative reward is normalized is_normalized = all(reward.is_normalized for reward in components) - # Jit-able method computing the product of reward components - @nb.jit(nopython=True, cache=True, fastmath=True) - def geometric_mean( - values: Tuple[Optional[float], ...]) -> Optional[float]: - """Compute the product of all the reward components that has - been evaluated, filtering out the others. - - This method returns `None` if no reward component has been - evaluated. - - :param values: Sequence of scalar value for reward components that - has been evaluated, `None` otherwise, with the same - ordering as 'components'. - - :returns: Scalar value if at least one of the reward component has - been evaluated, `None` otherwise. - """ - total, any_value, n_values = 1.0, False, 0 - for value in values: - if value is not None: - total *= value - any_value = True - n_values += 1 - return math.pow(total, 1.0 / n_values) if any_value else None - # Call base implementation super().__init__(env, name, components, geometric_mean, is_normalized) diff --git a/python/gym_jiminy/common/gym_jiminy/common/quantities/generic.py b/python/gym_jiminy/common/gym_jiminy/common/quantities/generic.py index ed5e148da..d893d336e 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/quantities/generic.py +++ b/python/gym_jiminy/common/gym_jiminy/common/quantities/generic.py @@ -23,7 +23,7 @@ from ..bases import ( InterfaceJiminyEnv, InterfaceQuantity, AbstractQuantity, StateQuantity, - QuantityEvalMode) + QuantityEvalMode, partial_hashable) from ..utils import ( mean, matrix_to_rpy, matrix_to_quat, quat_apply, remove_yaw_from_quat, quat_interpolate_middle) @@ -949,6 +949,39 @@ def refresh(self) -> np.ndarray: return self._xyzquats +@nb.jit(nopython=True, cache=True, fastmath=True) +def position_average(value: np.ndarray, out: np.ndarray) -> None: + """Compute the mean of an array over its last axis only. + + :param value: N-dimensional array from which the last axis will be + reduced. + :param out: Pre-allocated array in which to store the result. + """ + out[:] = np.sum(value, -1) / value.shape[-1] + + +@nb.jit(nopython=True, cache=True, fastmath=True) +def quat_average_2d(quat: np.ndarray, out: np.ndarray) -> None: + """Compute the average of a batch of quaternions [qx, qy, qz, qw]. + + .. note:: + Jit-able specialization of `quat_average` for 2D matrices, with further + optimization for the special case where there is only 2 quaternions. + + :param quat: N-dimensional (N >= 2) array whose first dimension gathers the + 4 quaternion coordinates [qx, qy, qz, qw]. + :param out: Pre-allocated array in which to store the result. + """ + num_quats = quat.shape[1] + if num_quats == 1: + out[:] = quat + elif num_quats == 2: + quat_interpolate_middle(quat[:, 0], quat[:, 1], out) + else: + _, eigvec = np.linalg.eigh(quat @ quat.T) + out[:] = eigvec[..., -1] + + @dataclass(unsafe_hash=True) class MultiFrameMeanXYZQuat(InterfaceQuantity[np.ndarray]): """Spatial vector representation (X, Y, Z, QuatX, QuatY, QuatZ, QuatW) of @@ -1014,44 +1047,6 @@ def __init__(self, mode=mode))), auto_refresh=False) - # Jit-able method specialization of `np.mean` for `axis=-1` - @nb.jit(nopython=True, cache=True, fastmath=True) - def position_average(value: np.ndarray, out: np.ndarray) -> None: - """Compute the mean of an array over its last axis only. - - :param value: N-dimensional array from which the last axis will be - reduced. - :param out: Pre-allocated array in which to store the result. - """ - out[:] = np.sum(value, -1) / value.shape[-1] - - self._position_average = position_average - - # Jit-able specialization of `quat_average` for 2D matrices - @nb.jit(nopython=True, cache=True, fastmath=True) - def quat_average_2d(quat: np.ndarray, out: np.ndarray) -> None: - """Compute the average of a batch of quaternions [qx, qy, qz, qw]. - - .. note:: - Jit-able specialization of `quat_average` for 2D matrices, with - further optimization for the special case where there is only 2 - quaternions. - - :param quat: N-dimensional (N >= 2) array whose first dimension - gathers the 4 quaternion coordinates [qx, qy, qz, qw]. - :param out: Pre-allocated array in which to store the result. - """ - num_quats = quat.shape[1] - if num_quats == 1: - out[:] = quat - elif num_quats == 2: - quat_interpolate_middle(quat[:, 0], quat[:, 1], out) - else: - _, eigvec = np.linalg.eigh(quat @ quat.T) - out[:] = eigvec[..., -1] - - self._quat_average = quat_average_2d - # Pre-allocate memory for the mean for mean pose vector XYZQuat self._xyzquat_mean = np.zeros((7,)) @@ -1061,10 +1056,10 @@ def quat_average_2d(quat: np.ndarray, out: np.ndarray) -> None: def refresh(self) -> np.ndarray: # Compute the mean translation - self._position_average(self.positions.get(), self._position_mean_view) + position_average(self.positions.get(), self._position_mean_view) # Compute the mean quaternion - self._quat_average(self.quats.get(), self._quat_mean_view) + quat_average_2d(self.quats.get(), self._quat_mean_view) return self._xyzquat_mean @@ -1726,6 +1721,33 @@ class EnergyGenerationMode(IntEnum): """ +@nb.jit(nopython=True, cache=True, fastmath=True) +def compute_power(generator_mode: int, # EnergyGenerationMode + motor_velocities: np.ndarray, + motor_efforts: np.ndarray) -> float: + """Compute the total instantaneous mechanical power consumption of all + motors. + + :param generator_mode: Specify what happens to the energy generated by + motors when breaking. + :param motor_velocities: Velocity of all the motors before transmission as + a 1D array. The order must be consistent with the + motor indices. + :param motor_efforts: Effort of all the motors before transmission as a 1D + array. The order must be consistent with the motor + indices. + """ + if generator_mode in (_CHARGE, _LOST_GLOBAL): + total_power = np.dot(motor_velocities, motor_efforts) + if generator_mode == _CHARGE: + return total_power + return max(total_power, 0.0) + motor_powers = motor_velocities * motor_efforts + if generator_mode == _LOST_EACH: + return np.sum(np.maximum(motor_powers, 0.0)) + return np.sum(np.abs(motor_powers)) + + @dataclass(unsafe_hash=True) class MechanicalPowerConsumption(InterfaceQuantity[float]): """Instantaneous power consumption induced by all the motors. @@ -1766,33 +1788,6 @@ def __init__( self.generator_mode = generator_mode self.mode = mode - # Jit-able method computing the total instantaneous power consumption - @nb.jit(nopython=True, cache=True, fastmath=True) - def _compute_power(generator_mode: int, # EnergyGenerationMode - motor_velocities: np.ndarray, - motor_efforts: np.ndarray) -> float: - """Compute the total instantaneous mechanical power consumption of - all motors. - - :param generator_mode: Specify what happens to the energy generated - by motors when breaking. - :param motor_velocities: Velocity of all the motors before - transmission as a 1D array. The order must - be consistent with the motor indices. - :param motor_efforts: Effort of all the motors before transmission - as a 1D array. The order must be consistent - with the motor indices. - """ - if generator_mode in (_CHARGE, _LOST_GLOBAL): - total_power = np.dot(motor_velocities, motor_efforts) - if generator_mode == _CHARGE: - return total_power - return max(total_power, 0.0) - motor_powers = motor_velocities * motor_efforts - if generator_mode == _LOST_EACH: - return np.sum(np.maximum(motor_powers, 0.0)) - return np.sum(np.abs(motor_powers)) - # Call base implementation super().__init__( env, @@ -1808,7 +1803,8 @@ def _compute_power(generator_mode: int, # EnergyGenerationMode kinematic_level=pin.KinematicLevel.VELOCITY, is_motor_side=True, mode=self.mode)), - op=partial(_compute_power, int(self.generator_mode))))), + op=partial_hashable( + compute_power, int(self.generator_mode))))), auto_refresh=False) def refresh(self) -> float: diff --git a/python/gym_jiminy/common/gym_jiminy/common/quantities/locomotion.py b/python/gym_jiminy/common/gym_jiminy/common/quantities/locomotion.py index 48fe4f7d2..8ce5a46f4 100644 --- a/python/gym_jiminy/common/gym_jiminy/common/quantities/locomotion.py +++ b/python/gym_jiminy/common/gym_jiminy/common/quantities/locomotion.py @@ -82,30 +82,6 @@ def sanitize_foot_frame_names( return sorted(frame_names) -@nb.jit(nopython=True, cache=True, fastmath=True) -def translate_position_odom(position: np.ndarray, - odom_pose: np.ndarray, - out: np.ndarray) -> None: - """Translate a single or batch of 2D position vector (X, Y) from world to - local frame. - - :param position: Batch of positions vectors as a 2D array whose - first dimension gathers the 2 spatial coordinates - (X, Y) while the second corresponds to the - independent points. - :param odom_pose: Reference odometry pose as a 1D array gathering the 2 - position and 1 orientation coordinates in world plane - (X, Y), (Yaw,) respectively. - :param out: Pre-allocated array in which to store the result. - """ - # out = R(yaw).T @ (position - position_ref) - position_ref, yaw_ref = odom_pose[:2], odom_pose[2] - pos_rel_x, pos_rel_y = position - position_ref - cos_yaw, sin_yaw = math.cos(yaw_ref), math.sin(yaw_ref) - out[0] = + cos_yaw * pos_rel_x + sin_yaw * pos_rel_y - out[1] = - sin_yaw * pos_rel_x + cos_yaw * pos_rel_y - - @nb.jit(nopython=True, cache=True, fastmath=True) def compute_height(base_pos: np.ndarray, contacts_pos: np.ndarray) -> float: """Compute the height of the robot, which is defined as the maximum @@ -165,9 +141,11 @@ def __init__(self, parent, requirements=dict( base_pos=(FramePosition, dict( - frame_name="root_joint")), + frame_name="root_joint", + mode=mode)), contacts_pos=(MultiFramePosition, dict( - frame_names=frame_names))), + frame_names=frame_names, + mode=mode))), auto_refresh=False) def refresh(self) -> float: @@ -673,6 +651,25 @@ def refresh(self) -> np.ndarray: return self.data.get() +@nb.jit(nopython=True, cache=True, fastmath=True) +def translate_positions(position: np.ndarray, + position_ref: np.ndarray, + rotation_ref: np.ndarray, + out: np.ndarray) -> None: + """Translate a batch of 3D position vectors (X, Y, Z) from world to local + frame. + + :param position: Batch of positions vectors as a 2D array whose first + dimension gathers the 3 spatial coordinates (X, Y, Z) + while the second corresponds to the independent points. + :param position_ref: Position of the reference frame in world. + :param rotation_ref: Orientation of the reference frame in world as a + rotation matrix. + :param out: Pre-allocated array in which to store the result. + """ + out[:] = rotation_ref.T @ (position - position_ref[:, np.newaxis]) + + @dataclass(unsafe_hash=True) class MultiFootRelativeXYZQuat(InterfaceQuantity[np.ndarray]): """Relative position and orientation of the feet of a legged robot wrt @@ -741,28 +738,6 @@ def __init__(self, mode=mode))), auto_refresh=False) - # Jit-able method translating multiple positions to local frame - @nb.jit(nopython=True, cache=True, fastmath=True) - def translate_positions(position: np.ndarray, - position_ref: np.ndarray, - rotation_ref: np.ndarray, - out: np.ndarray) -> None: - """Translate a batch of 3D position vectors (X, Y, Z) from world to - local frame. - - :param position: Batch of positions vectors as a 2D array whose - first dimension gathers the 3 spatial coordinates - (X, Y, Z) while the second corresponds to the - independent points. - :param position_ref: Position of the reference frame in world. - :param rotation_ref: Orientation of the reference frame in world as - a rotation matrix. - :param out: Pre-allocated array in which to store the result. - """ - out[:] = rotation_ref.T @ (position - position_ref[:, np.newaxis]) - - self._translate = translate_positions - # Mean orientation as a rotation matrix self._rot_mean = np.zeros((3, 3)) @@ -793,10 +768,10 @@ def refresh(self) -> np.ndarray: # (double geodesic), to be consistent with the method that was used to # compute the mean foot pose. This way, the norm of the relative # position is not affected by the orientation of the feet. - self._translate(positions, - position_mean, - self._rot_mean, - self._foot_position_view) + translate_positions(positions, + position_mean, + self._rot_mean, + self._foot_position_view) # Compute relative frame orientations quat_multiply(quat_mean[:, np.newaxis], @@ -884,6 +859,29 @@ def refresh(self) -> np.ndarray: return self._com_data +@nb.jit(nopython=True, cache=True, fastmath=True) +def translate_position_odom(position: np.ndarray, + odom_pose: np.ndarray, + out: np.ndarray) -> None: + """Translate a single or batch of 2D position vector (X, Y) from world to + local frame. + + :param position: Batch of positions vectors as a 2D array whose first + dimension gathers the 2 spatial coordinates (X, Y) while + the second corresponds to the independent points. + :param odom_pose: Reference odometry pose as a 1D array gathering the 2 + position and 1 orientation coordinates in world plane + (X, Y), (Yaw,) respectively. + :param out: Pre-allocated array in which to store the result. + """ + # out = R(yaw).T @ (position - position_ref) + position_ref, yaw_ref = odom_pose[:2], odom_pose[2] + pos_rel_x, pos_rel_y = position - position_ref + cos_yaw, sin_yaw = math.cos(yaw_ref), math.sin(yaw_ref) + out[0] = + cos_yaw * pos_rel_x + sin_yaw * pos_rel_y + out[1] = - sin_yaw * pos_rel_x + cos_yaw * pos_rel_y + + @dataclass(unsafe_hash=True) class ZeroMomentPoint(AbstractQuantity[np.ndarray]): """Zero-Tilting Moment Point (ZMP), also called Center of Pressure (CoP). @@ -1098,6 +1096,36 @@ def refresh(self) -> np.ndarray: return self._dcm +@nb.jit(nopython=True, cache=True, fastmath=True) +def normalize_spatial_forces(lambda_c: np.ndarray, + index_start: int, + index_end: int, + robot_weight: float, + out: np.ndarray) -> None: + """Compute the spatial forces of all the constraints associated with + contact frames and collision bodies, normalized by the total weight of the + robot. + + :param lambda_c: Stacked lambda multipliers all the constraints. + :param index_start: First index of the constraints associated with contact + frames and collisions bodies. + :param index_end: One-past-last index of the constraints associated with + contact frames and collisions bodies. + :param robot_weight: Total weight of the robot which will be used to + rescale the spatial forces. + :param out: Pre-allocated array in which to store the result. + """ + # Extract constraint lambdas of contacts and collisions from state + lambda_ = lambda_c[index_start:index_end].reshape((-1, 4)).T + + # Extract references to all the spatial forces + forces_linear, forces_angular_z = lambda_[:3], lambda_[3] + + # Scale the spatial forces by the weight of the robot + out[:3] = forces_linear / robot_weight + out[5] = forces_angular_z / robot_weight + + @dataclass(unsafe_hash=True) class MultiContactNormalizedSpatialForce(AbstractQuantity[np.ndarray]): """Standardized spatial forces applied on all contact points and collision @@ -1140,38 +1168,6 @@ def __init__(self, mode=mode, auto_refresh=False) - # Jit-able method computing the normalized spatial forces - @nb.jit(nopython=True, cache=True, fastmath=True) - def normalize_spatial_forces(lambda_c: np.ndarray, - index_start: int, - index_end: int, - robot_weight: float, - out: np.ndarray) -> None: - """Compute the spatial forces of all the constraints associated - with contact frames and collision bodies, normalized by the total - weight of the robot. - - :param lambda_c: Stacked lambda multipliers all the constraints. - :param index_start: First index of the constraints associated with - contact frames and collisions bodies. - :param index_end: One-past-last index of the constraints associated - with contact frames and collisions bodies. - :param robot_weight: Total weight of the robot which will be used - to rescale the spatial forces. - :param out: Pre-allocated array in which to store the result. - """ - # Extract constraint lambdas of contacts and collisions from state - lambda_ = lambda_c[index_start:index_end].reshape((-1, 4)).T - - # Extract references to all the spatial forces - forces_linear, forces_angular_z = lambda_[:3], lambda_[3] - - # Scale the spatial forces by the weight of the robot - out[:3] = forces_linear / robot_weight - out[5] = forces_angular_z / robot_weight - - self._normalize_spatial_forces = normalize_spatial_forces - # Weight of the robot self._robot_weight: float = float("nan") @@ -1235,7 +1231,7 @@ def initialize(self) -> None: def refresh(self) -> np.ndarray: state = self.state.get() - self._normalize_spatial_forces( + normalize_spatial_forces( state.lambda_c, *self._contact_slice, self._robot_weight, @@ -1244,6 +1240,49 @@ def refresh(self) -> np.ndarray: return self._force_spatial_rel_batch +@nb.jit(nopython=True, cache=True, fastmath=True) +def normalize_vertical_forces( + lambda_c: np.ndarray, + foot_slices: Tuple[Tuple[int, int], ...], + vertical_transform_batches: Tuple[np.ndarray, ...], + robot_weight: float, + out: np.ndarray) -> None: + """Compute the sum of the vertical forces in world frame of all the + constraints associated with contact frames and collision bodies, normalized + by the total weight of the robot. + + :param lambda_c: Stacked lambda multipliers all the constraints. + :param foot_slices: Slices of lambda multiplier of the constraints + associated with contact frames and collisions bodies + acting each foot, as a sequence of pairs (index_start, + index_end) corresponding to the first and one-past-last + indices respectively. + :param vertical_transform_batches: + Last row of the rotation matrices from world to local contact frame + associated with all contact and collision constraints acting on each + foot, as a list of 2D arrays. The first dimension gathers the 3 spatial + coordinates while the second corresponds to the N individual + constraints on each foot. + :param robot_weight: Total weight of the robot which will be used to + rescale the vertical forces. + :param out: Pre-allocated array in which to store the result. + """ + for i, ((index_start, index_end), vertical_transforms) in ( + enumerate(zip(foot_slices, vertical_transform_batches))): + # Extract constraint multipliers from state + lambda_ = lambda_c[index_start:index_end].reshape((-1, 4)).T + + # Extract references to all the linear forces + # forces_angular = np.array([0.0, 0.0, lambda_[3]]) + forces_linear = lambda_[:3] + + # Compute vertical forces in world frame and aggregate them + f_z_world = np.sum(vertical_transforms * forces_linear) + + # Scale the vertical forces by the weight of the robot + out[i] = f_z_world / robot_weight + + @dataclass(unsafe_hash=True) class MultiFootNormalizedForceVertical(AbstractQuantity[np.ndarray]): """Standardized total vertical forces apply on each foot in world frame. @@ -1299,51 +1338,6 @@ def __init__(self, mode=mode, auto_refresh=False) - # Jit-able method computing the normalized vertical forces - @nb.jit(nopython=True, cache=True, fastmath=True) - def normalize_vertical_forces( - lambda_c: np.ndarray, - foot_slices: Tuple[Tuple[int, int], ...], - vertical_transform_batches: Tuple[np.ndarray, ...], - robot_weight: float, - out: np.ndarray) -> None: - """Compute the sum of the vertical forces in world frame of all the - constraints associated with contact frames and collision bodies, - normalized by the total weight of the robot. - - :param lambda_c: Stacked lambda multipliers all the constraints. - :param foot_slices: Slices of lambda multiplier of the constraints - associated with contact frames and collisions - bodies acting each foot, as a sequence of pairs - (index_start, index_end) corresponding to the - first and one-past-last indices respectively. - :param vertical_transform_batches: - Last row of the rotation matrices from world to local contact - frame associated with all contact and collision constraints - acting on each foot, as a list of 2D arrays. The first - dimension gathers the 3 spatial coordinates while the second - corresponds to the N individual constraints on each foot. - :param robot_weight: Total weight of the robot which will be used - to rescale the vertical forces. - :param out: Pre-allocated array in which to store the result. - """ - for i, ((index_start, index_end), vertical_transforms) in ( - enumerate(zip(foot_slices, vertical_transform_batches))): - # Extract constraint multipliers from state - lambda_ = lambda_c[index_start:index_end].reshape((-1, 4)).T - - # Extract references to all the linear forces - # forces_angular = np.array([0.0, 0.0, lambda_[3]]) - forces_linear = lambda_[:3] - - # Compute vertical forces in world frame and aggregate them - f_z_world = np.sum(vertical_transforms * forces_linear) - - # Scale the vertical forces by the weight of the robot - out[i] = f_z_world / robot_weight - - self._normalize_vertical_forces = normalize_vertical_forces - # Weight of the robot self._robot_weight: float = float("nan") @@ -1450,11 +1444,11 @@ def refresh(self) -> np.ndarray: # Compute the normalized sum of the vertical forces in world frame state = self.state.get() - self._normalize_vertical_forces(state.lambda_c, - self._foot_slices, - self._vertical_transform_batches, - self._robot_weight, - self._vertical_force_batch) + normalize_vertical_forces(state.lambda_c, + self._foot_slices, + self._vertical_transform_batches, + self._robot_weight, + self._vertical_force_batch) return self._vertical_force_batch diff --git a/python/gym_jiminy/examples/pipeline_benchmark.py b/python/gym_jiminy/examples/pipeline_benchmark.py index 1890f17dd..dc2557e4c 100644 --- a/python/gym_jiminy/examples/pipeline_benchmark.py +++ b/python/gym_jiminy/examples/pipeline_benchmark.py @@ -43,7 +43,7 @@ ), ) -# Run in 30.7s on jiminy==1.8.11 (29.7s with PGO, 28.4s with eigen-dev) +# Run in 27.4s on jiminy==1.8.11 (PGO + eigen-dev) env.reset() action = env.action time_start = time.time() diff --git a/python/gym_jiminy/unit_py/test_terminations.py b/python/gym_jiminy/unit_py/test_terminations.py index 09e36400d..a12177ce3 100644 --- a/python/gym_jiminy/unit_py/test_terminations.py +++ b/python/gym_jiminy/unit_py/test_terminations.py @@ -1,6 +1,7 @@ # mypy: disable-error-code="no-untyped-def, var-annotated" """ TODO: Write documentation """ +import gc from operator import sub import unittest @@ -75,32 +76,30 @@ def test_composition(self): def test_drift_tracking(self): """ TODO: Write documentation """ - termination_pos_config = ("pos", (FramePosition, {}), -0.2, 0.3, sub) + termination_pos_config = ("pos", (FramePosition, {}), 0.2, sub) termination_rot_config = ( "rot", (FrameOrientation, dict(type=OrientationType.QUATERNION)), - np.array([-0.5, -0.6, -0.7]), - np.array([0.7, 0.5, 0.6]), + 0.6, quat_difference) - for i, (is_truncation, is_training_only) in enumerate(( - (False, False), (True, False), (False, True))): + for is_truncation, is_training_only in ( + (False, False), (True, False), (False, True)): termination_pos, termination_rot = ( DriftTrackingQuantityTermination( self.env, - f"drift_tracking_{name}_{i}", + f"drift_tracking_{name}", lambda mode: (quantity_cls, dict( **quantity_kwargs, frame_name="root_joint", mode=mode)), - low=low, - high=high, + thr=thr, horizon=0.3, grace_period=0.2, op=op, is_truncation=is_truncation, training_only=is_training_only - ) for name, (quantity_cls, quantity_kwargs), low, high, op in ( + ) for name, (quantity_cls, quantity_kwargs), thr, op in ( termination_pos_config, termination_rot_config)) self.env.stop() @@ -136,12 +135,16 @@ def test_drift_tracking(self): assert terminated ^ termination.is_truncation elif is_active: value = termination.data.get() - assert np.all(value >= termination.low) - assert np.all(value <= termination.high) + assert np.linalg.norm(value) <= termination.high _, _, terminated, truncated, _ = self.env.step(action) if terminated or truncated: break + del termination + del termination_pos + del termination_rot + gc.collect() + def test_shift_tracking(self): """ TODO: Write documentation """ @@ -152,12 +155,12 @@ def test_shift_tracking(self): 0.3, quat_difference) - for i, (is_truncation, training_only) in enumerate(( - (False, False), (True, False), (False, True))): + for is_truncation, training_only in ( + (False, False), (True, False), (False, True)): termination_pos, termination_rot = ( ShiftTrackingQuantityTermination( self.env, - f"shift_tracking_{name}_{i}", + f"shift_tracking_{name}", lambda mode: (quantity_cls, dict( **quantity_kwargs, frame_name="root_joint", @@ -219,6 +222,11 @@ def test_shift_tracking(self): if terminated or truncated: break + del termination + del termination_pos + del termination_rot + gc.collect() + def test_base_roll_pitch(self): """ TODO: Write documentation """ diff --git a/python/jiminy_py/src/jiminy_py/dynamics.py b/python/jiminy_py/src/jiminy_py/dynamics.py index 145c6f51b..83441c4cd 100644 --- a/python/jiminy_py/src/jiminy_py/dynamics.py +++ b/python/jiminy_py/src/jiminy_py/dynamics.py @@ -396,7 +396,7 @@ def get(self, t: float, mode: TrajectoryTimeMode = 'raise') -> State: else: t = t_start else: - t = max(t, t_start) # Clipping right it is sufficient + t = min(max(t, t_start), t_end) # Rounding time to avoid cache miss issues # Note that `int(x + 0.5)` is faster than `round(x)`.