Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Various bug fixes. #466

Merged
merged 3 commits into from
Dec 7, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion core/src/utilities/Json.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ namespace jiminy
template<>
Json::Value convertToJson<configHolder_t>(configHolder_t const & value)
{
Json::Value root;
Json::Value root{Json::objectValue};
AppendBoostVariantToJson visitor(root);
for (auto const & option : value)
{
Expand Down
14 changes: 7 additions & 7 deletions python/gym_jiminy/common/gym_jiminy/common/bases/block_bases.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ def __init__(self,
super().__init__(**kwargs) # type: ignore[call-arg]

# Refresh the observation and action spaces
self._refresh_observation_space()
self._refresh_action_space()
self._initialize_observation_space()
self._initialize_action_space()

# Assertion(s) for type checker
assert (self.observation_space is not None and
Expand Down Expand Up @@ -95,7 +95,7 @@ def _setup(self) -> None:
state of the block.
"""

def _refresh_observation_space(self) -> None:
def _initialize_observation_space(self) -> None:
"""Configure the observation of the block.

.. note::
Expand All @@ -105,7 +105,7 @@ def _refresh_observation_space(self) -> None:
"""
raise NotImplementedError

def _refresh_action_space(self) -> None:
def _initialize_action_space(self) -> None:
"""Configure the action of the block.

.. note::
Expand Down Expand Up @@ -150,7 +150,7 @@ def __init__(self, *args: Any, **kwargs: Any) -> None:
# Initialize the block and observe interface
super().__init__(*args, **kwargs)

def _refresh_action_space(self) -> None:
def _initialize_action_space(self) -> None:
"""Configure the action space of the observer.

It does nothing but to return the action space of the environment
Expand Down Expand Up @@ -232,7 +232,7 @@ def __init__(self, *args: Any, **kwargs: Any) -> None:
# Initialize the block and control interface
super().__init__(*args, **kwargs)

def _refresh_observation_space(self) -> None:
def _initialize_observation_space(self) -> None:
"""Configure the observation space of the controller.

It does nothing but to return the observation space of the environment
Expand Down Expand Up @@ -293,7 +293,7 @@ def get_fieldnames(self) -> FieldNested:
monitor the internal state of the controller.
"""

BaseControllerBlock._refresh_action_space.__doc__ = \
BaseControllerBlock._initialize_action_space.__doc__ = \
"""Configure the action space of the controller.

.. note::
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ def get_observation(self) -> DataNested:
# methods to override:
# ----------------------------

def _refresh_observation_space(self) -> None:
def _initialize_observation_space(self) -> None:
"""Configure the observation space.
"""
raise NotImplementedError
Expand Down Expand Up @@ -109,7 +109,7 @@ def __init__(self, *args: Any, **kwargs: Any) -> None:
# methods to override:
# ----------------------------

def _refresh_action_space(self) -> None:
def _initialize_action_space(self) -> None:
"""Configure the action space.
"""
raise NotImplementedError
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ def __init__(self,
# Initialize the controller
super().__init__(env, update_ratio)

def _refresh_action_space(self) -> None:
def _initialize_action_space(self) -> None:
"""Configure the action space of the controller.

The action spaces corresponds to the position and velocity of motors
Expand Down
68 changes: 51 additions & 17 deletions python/gym_jiminy/common/gym_jiminy/common/envs/env_generic.py
Original file line number Diff line number Diff line change
Expand Up @@ -180,8 +180,8 @@ def __init__(self,
# Refresh the observation and action spaces.
# Note that it is necessary to refresh the action space before the
# observation one, since it may be useful to observe the action.
self._refresh_action_space()
self._refresh_observation_space()
self._initialize_action_space()
self._initialize_observation_space()

# Assertion(s) for type checker
assert (isinstance(self.observation_space, spaces.Space) and
Expand Down Expand Up @@ -256,7 +256,7 @@ def _get_state_space(self,

This method is not meant to be overloaded in general since the
definition of the state space is mostly consensual. One must rather
overload `_refresh_observation_space` to customize the observation
overload `_initialize_observation_space` to customize the observation
space as a whole.

:param use_theoretical_model: Whether to compute the state space
Expand Down Expand Up @@ -337,7 +337,7 @@ def _get_sensors_space(self) -> gym.Space:
.. warning:
This method is not meant to be overloaded in general since the
definition of the sensor space is mostly consensual. One must
rather overload `_refresh_observation_space` to customize the
rather overload `_initialize_observation_space` to customize the
observation space as a whole.
"""
# Define some proxies for convenience
Expand Down Expand Up @@ -445,7 +445,7 @@ def _get_sensors_space(self) -> gym.Space:
for (key, min_val), max_val in zip(
sensor_space_lower.items(), sensor_space_upper.values())))

def _refresh_action_space(self) -> None:
def _initialize_action_space(self) -> None:
"""Configure the action space of the environment.

The action is a vector gathering the torques of the actuator of the
Expand Down Expand Up @@ -644,8 +644,11 @@ def reset(self,
self.simulator.start(
qpos, qvel, None, self.simulator.use_theoretical_model)

# Initialize shared buffers
self._initialize_buffers()

# Update shared buffers
self._refresh_internal()
self._refresh_buffers()

# Initialize the observer.
# Note that it is responsible of refreshing the environment's
Expand All @@ -657,14 +660,14 @@ def reset(self,
self.sensors_data)

# Make sure the state is valid, otherwise there `refresh_observation`
# and `_refresh_observation_space` are probably inconsistent.
# and `_initialize_observation_space` are probably inconsistent.
try:
obs = clip(self.observation_space, self.get_observation())
except (TypeError, ValueError) as e:
raise RuntimeError(
"The observation computed by `refresh_observation` is "
"inconsistent with the observation space defined by "
"`_refresh_observation_space` at initialization.") from e
"`_initialize_observation_space` at initialization.") from e

# Make sure there is no 'nan' value in observation
for value in tree.flatten(obs):
Expand Down Expand Up @@ -753,7 +756,7 @@ def step(self,
self.simulator.step(self.step_dt)

# Update shared buffers
self._refresh_internal()
self._refresh_buffers()

# Update the observer at the end of the step. Indeed, internally,
# it is called at the beginning of the every integration steps,
Expand Down Expand Up @@ -1188,7 +1191,7 @@ def _setup(self) -> None:
framesForwardKinematics(
self.robot.pinocchio_model, self.robot.pinocchio_data, qpos)

def _refresh_observation_space(self) -> None:
def _initialize_observation_space(self) -> None:
"""Configure the observation of the environment.

By default, the observation is a dictionary gathering the current
Expand Down Expand Up @@ -1277,17 +1280,42 @@ def _sample_state(self) -> Tuple[np.ndarray, np.ndarray]:

return qpos, qvel

def _refresh_internal(self) -> None:
"""Refresh internal buffers.
def _initialize_buffers(self) -> None:
"""Initialize internal buffers for fast access to shared memory or to
avoid redundant computations.

.. note::
This method is called at `reset`, right after
`self.simulator.start`. At this point, the simulation is running
but `refresh_observation` has never been called, so that it can be
used to initialize buffers involving the engine state but required
to refresh the observation. Note that it is not appropriate to
initialize buffers that would be used by `compute_command`.

.. note::
Buffers requiring manual update must be refreshed using
`_refresh_buffers` method.
"""

def _refresh_buffers(self) -> None:
"""Refresh internal buffers that must be updated manually.

.. note::
This method is called right after every internal `engine.step`, so
it is the right place to update shared data between `is_done` and
`compute_reward`. Be careful when using it to share data with
`refresh_observation`, but the later is called at `self.observe_dt`
update period, which the others are called at `self.step_dt` update
period. `self.observe_dt` is likely to different from `self.step`,
unless configured otherwise by overloading `_setup` method.
`compute_reward`.

.. note::
`_initialize_buffers` method can be used to initialize buffers that
may requires special care.

.. warning::
Be careful when using it to update buffers that are used by
`refresh_observation`. The later is called at `self.observe_dt`
update period, while the others are called at `self.step_dt` update
period. `self.observe_dt` is likely to be different from
`self.step_dt`, unless configured manually when overloading
`_setup` method.
"""

def refresh_observation(self) -> None: # type: ignore[override]
Expand Down Expand Up @@ -1337,6 +1365,12 @@ def compute_command(self,
overloading this method to clip the action if necessary to make sure it
does not violate the lower and upper bounds.

.. warning::
There is not good place to initialize buffers that are necessary to
compute the command. The only solution for now is to define
initialization inside this method itself, using the safeguard
`if not self.simulator.is_simulation_running:`.

:param measure: Observation of the environment.
:param action: Desired motors efforts.
"""
Expand Down
6 changes: 3 additions & 3 deletions python/gym_jiminy/envs/gym_jiminy/envs/acrobot.py
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ def _setup(self) -> None:
engine_options["stepper"]["dtMax"] = CONTROL_DT
self.simulator.engine.set_options(engine_options)

def _refresh_observation_space(self) -> None:
def _initialize_observation_space(self) -> None:
"""Configure the observation of the environment.

Only the state is observable, while by default, the current time,
Expand All @@ -149,7 +149,7 @@ def refresh_observation(self, *args: Any, **kwargs: Any) -> None:
self.__state_view[0][:] = self.__state[0]
self.__state_view[1][:] = self.__state[1]

def _refresh_action_space(self) -> None:
def _initialize_action_space(self) -> None:
"""Configure the action space of the environment.

Replace the action space by its discrete representation depending on
Expand All @@ -158,7 +158,7 @@ def _refresh_action_space(self) -> None:
if not self.continuous:
self.action_space = gym.spaces.Discrete(len(self.AVAIL_CTRL))
else:
super()._refresh_action_space()
super()._initialize_action_space()

def _sample_state(self) -> Tuple[np.ndarray, np.ndarray]:
"""Returns a valid configuration and velocity for the robot.
Expand Down
2 changes: 1 addition & 1 deletion python/gym_jiminy/envs/gym_jiminy/envs/ant.py
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ def _sample_state(self) -> Tuple[np.ndarray, np.ndarray]:

return qpos, qvel

def _refresh_observation_space(self) -> None:
def _initialize_observation_space(self) -> None:
""" TODO: Write documentation.

The observation space comprises:
Expand Down
6 changes: 3 additions & 3 deletions python/gym_jiminy/envs/gym_jiminy/envs/cartpole.py
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ def _setup(self) -> None:
engine_options["stepper"]["dtMax"] = CONTROL_DT
self.simulator.engine.set_options(engine_options)

def _refresh_observation_space(self) -> None:
def _initialize_observation_space(self) -> None:
"""Configure the observation of the environment.

Implement the official Gym cartpole-v1 action space. Only the state is
Expand All @@ -163,7 +163,7 @@ def _refresh_observation_space(self) -> None:
self.observation_space = spaces.Box(
low=-high, high=high, dtype=np.float64)

def _refresh_action_space(self) -> None:
def _initialize_action_space(self) -> None:
""" TODO: Write documentation.

Replace the action space by its discrete representation depending on
Expand All @@ -172,7 +172,7 @@ def _refresh_action_space(self) -> None:
if not self.continuous:
self.action_space = spaces.Discrete(len(self.AVAIL_CTRL))
else:
super()._refresh_action_space()
super()._initialize_action_space()

def _sample_state(self) -> Tuple[np.ndarray, np.ndarray]:
""" TODO: Write documentation.
Expand Down
2 changes: 2 additions & 0 deletions python/jiminy_py/src/jiminy_py/log.py
Original file line number Diff line number Diff line change
Expand Up @@ -312,6 +312,8 @@ def build_robot_from_log(
robot.initialize(urdf_path, has_freeflyer, mesh_package_dirs)
robot.set_options(all_options["system"]["robot"])
robot.pinocchio_model.loadFromString(pinocchio_model_str)
robot.pinocchio_data.loadFromString(
robot.pinocchio_model.createData().saveToString())

return robot

Expand Down