Skip to content

Commit

Permalink
[misc] Various minor improvements. (#848)
Browse files Browse the repository at this point in the history
* [gym_jiminy/common] Clip velocity/acceleration for instantaneously PD target update.
* [gym_jiminy/common] Fix plot of manually registered env variables.
* [python/simulator] Fix replay of extra log files and trajectories.
* [misc] Rename 'mesh_path_dir' in 'mesh_dir_path' for consistency.
* [misc] Cleanup linux build from source script.
  • Loading branch information
duburcqa authored Dec 13, 2024
1 parent 58e9b39 commit 0373511
Show file tree
Hide file tree
Showing 17 changed files with 96 additions and 75 deletions.
1 change: 1 addition & 0 deletions .github/workflows/linux.yml
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,7 @@ jobs:
cd "${RootDir}/build"
cmake "${RootDir}" -Wdev \
-DCMAKE_INSTALL_PREFIX="$InstallDir" -DCMAKE_PREFIX_PATH="$InstallDir" \
-DCMAKE_INTERPROCEDURAL_OPTIMIZATION=${{ (matrix.BUILD_TYPE == 'Debug' && 'OFF') || 'ON' }} \
-DBOOST_ROOT="$InstallDir" -DBoost_INCLUDE_DIR="$InstallDir/include" \
-DBoost_NO_SYSTEM_PATHS=TRUE -DBoost_NO_BOOST_CMAKE=TRUE -DBoost_USE_STATIC_LIBS=ON \
-DPYTHON_EXECUTABLE="${PYTHON_EXECUTABLE}" \
Expand Down
25 changes: 14 additions & 11 deletions build_tools/build_install_deps_unix.sh
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ if [ -z ${CXX_COMPILER} ]; then
fi

### Set common CMAKE_C/CXX_FLAGS
CXX_FLAGS="${CXX_FLAGS} -Wno-enum-constexpr-conversion"
CXX_FLAGS="${CXX_FLAGS} -Wno-unknown-warning-option -Wno-enum-constexpr-conversion"
if [ "${BUILD_TYPE}" == "Release" ]; then
CXX_FLAGS="${CXX_FLAGS} -DNDEBUG -O3"
elif [ "${BUILD_TYPE}" == "Debug" ]; then
Expand Down Expand Up @@ -94,19 +94,17 @@ unset Boost_ROOT
# - Boost >= 1.75 is required to compile ouf-of-the-box on MacOS for intel and Apple Silicon
# - Boost < 1.77 causes compilation failure with gcc-12 if not patched
# - Boost >= 1.77 affects the memory layout to improve alignment, breaking retro-compatibility
# - Boost.Python == 1.87 fixes memory alignment issues (commit 4fc3afa3ac1a1edb61a92fccd31d305ba38213f8)
# - Boost.Python == 1.87 fixes memory alignment issues
if [ ! -d "${RootDir}/boost" ]; then
git clone --depth 1 https://github.com/boostorg/boost.git "${RootDir}/boost"
fi
rm -rf "${RootDir}/boost/build"
mkdir -p "${RootDir}/boost/build"
cd "${RootDir}/boost"
git reset --hard
git fetch origin "boost-1.86.0" && git checkout --force FETCH_HEAD || true
git fetch origin "boost-1.87.0" && git checkout --force FETCH_HEAD || true
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
cd "${RootDir}/boost/libs/python"
git fetch origin 4fc3afa3ac1a1edb61a92fccd31d305ba38213f8 && git checkout --force FETCH_HEAD || true

### Checkout eigen3
if [ ! -d "${RootDir}/eigen3" ]; then
Expand Down Expand Up @@ -245,7 +243,9 @@ PATH="${PATH}:$(dirname -- ${C_COMPILER})"

### Build and install the build tool b2 (build-ception !)
cd "${RootDir}/boost"
./bootstrap.sh --prefix="${InstallDir}" --with-python="${PYTHON_EXECUTABLE}"
./bootstrap.sh --with-toolset="$(basename -- ${C_COMPILER})" \
--prefix="${InstallDir}" \
--with-python="${PYTHON_EXECUTABLE}"

### File "project-config.jam" create by bootstrap must be edited manually
# to specify Python include dir manually, since it is not detected
Expand All @@ -258,6 +258,9 @@ ${PYTHON_CONFIG_JAM}

### Build and install and install boost
# (Replace -d0 option by -d1 and remove -q option to check compilation errors)
if [[ ${OSX_ARCHITECTURES} == *";"* ]] ; then
ArchB2="arm+x86"
fi
if [ "${BUILD_TYPE}" == "Release" ]; then
BuildTypeB2="release"
elif [ "${BUILD_TYPE}" == "Debug" ]; then
Expand All @@ -281,7 +284,7 @@ fi
./b2 --prefix="$InstallDir" --build-dir="$RootDir/boost/build" \
--debug-configuration \
--clean-all \
architecture= address-model=64 \
architecture="$ArchB2" address-model=64 \
variant="$BuildTypeB2"

# Compiling everything with static linkage except Boost::Python
Expand All @@ -290,7 +293,7 @@ mkdir -p "${RootDir}/boost/build"
--with-chrono --with-timer --with-date_time --with-system --with-test \
--with-filesystem --with-atomic --with-serialization --with-thread \
--build-type=minimal --layout=system --lto=on \
architecture= address-model=64 $DebugOptionsB2 \
architecture="$ArchB2" address-model=64 $DebugOptionsB2 \
threading=single link=static runtime-link=static \
cxxflags="${CXX_FLAGS} ${CXX_FLAGS_B2}" \
linkflags="${LINKER_FLAGS} ${CXX_FLAGS_B2}" \
Expand All @@ -302,7 +305,7 @@ mkdir -p "${RootDir}/boost/build"
./b2 --prefix="${InstallDir}" --build-dir="${RootDir}/boost/build" \
--with-python \
--build-type=minimal --layout=system --lto=on \
architecture= address-model=64 $DebugOptionsB2 \
architecture="$ArchB2" address-model=64 $DebugOptionsB2 \
threading=single link=shared runtime-link=shared \
cxxflags="${CXX_FLAGS} ${CXX_FLAGS_B2} -DNDEBUG" \
linkflags="${LINKER_FLAGS} ${CXX_FLAGS_B2} " \
Expand Down Expand Up @@ -450,7 +453,7 @@ cmake "${RootDir}/hpp-fcl" -Wno-dev -DCMAKE_CXX_STANDARD=17 \
-DBUILD_TESTING=OFF -DINSTALL_DOCUMENTATION=OFF -DENABLE_PYTHON_DOXYGEN_AUTODOC=OFF \
-DCMAKE_CXX_FLAGS_RELEASE_INIT="" -DCMAKE_CXX_FLAGS="${CXX_FLAGS} $(
) -Wno-unused-parameter -Wno-class-memaccess -Wno-sign-compare-Wno-conversion -Wno-ignored-qualifiers $(
) -Wno-uninitialized -Wno-maybe-uninitialized -Wno-deprecated-copy -Wno-unknown-warning-option $(
) -Wno-uninitialized -Wno-maybe-uninitialized -Wno-deprecated-copy $(
) -Wno-unknown-warning" -DCMAKE_BUILD_TYPE="${BUILD_TYPE}"
make install -j4

Expand All @@ -472,7 +475,7 @@ cmake "${RootDir}/pinocchio" -Wno-dev -DCMAKE_CXX_STANDARD=17 \
-DBUILD_WITH_OPENMP_SUPPORT=OFF -DGENERATE_PYTHON_STUBS=OFF -DBUILD_TESTING=OFF -DINSTALL_DOCUMENTATION=OFF \
-DCMAKE_CXX_FLAGS_RELEASE_INIT="" -DCMAKE_CXX_FLAGS="${CXX_FLAGS} -DBOOST_BIND_GLOBAL_PLACEHOLDERS $(
) -Wno-uninitialized -Wno-type-limits -Wno-unused-local-typedefs -Wno-extra $(
) -Wno-unknown-warning-option -Wno-unknown-warning" -DCMAKE_BUILD_TYPE="${BUILD_TYPE}"
) -Wno-unknown-warning" -DCMAKE_BUILD_TYPE="${BUILD_TYPE}"
make install -j4

# Copy cmake configuration files for cppad and cppadcodegen
Expand Down
6 changes: 1 addition & 5 deletions build_tools/build_install_deps_windows.ps1
Original file line number Diff line number Diff line change
Expand Up @@ -103,14 +103,10 @@ if (Test-Path -PathType Container "$RootDir/boost/build") {
New-Item -ItemType "directory" -Force -Path "$RootDir/boost/build"
Push-Location -Path "$RootDir/boost"
git reset --hard
git fetch origin "boost-1.86.0"
git fetch origin "boost-1.87.0"
git checkout --force FETCH_HEAD
git submodule --quiet foreach --recursive git reset --quiet --hard
git submodule --quiet update --init --recursive --depth 1 --jobs 8
Push-Location -Path "$RootDir/boost/libs/python"
git fetch origin 4fc3afa3ac1a1edb61a92fccd31d305ba38213f8
git checkout --force FETCH_HEAD
Pop-Location

### Checkout eigen3
# A specific commit from Aug 25, 2021 (post 3.4.0) fixes CXX STANDARD detection with MSVC
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -206,10 +206,28 @@ def pd_adapter(action: np.ndarray,
if is_instantaneous:
# Update the command state directly
if order == 0:
# Compute command velocity
velocity = (action - command_state[0]) / dt

# Clip command velocity
velocity = np.minimum(np.maximum(
velocity, command_state_lower[1]), command_state_upper[1])

# Update command position instantaneously
command_state[0] = action
command_state[1] = 0.0
else:
command_state[1] = action
# Compute command acceleration
acceleration = (action - command_state[1]) / dt

# Clip command acceleration
acceleration = np.minimum(np.maximum(
acceleration, command_state_lower[2]), command_state_upper[2])

# Update command velocity instantaneously
command_state[1] += acceleration * dt

# Hold the acceleration constant equal to zero
out[:] = 0.0
else:
if order == 0:
Expand Down
2 changes: 1 addition & 1 deletion python/gym_jiminy/common/gym_jiminy/common/envs/generic.py
Original file line number Diff line number Diff line change
Expand Up @@ -961,7 +961,7 @@ def plot(self,
tab_name = " ".join(filter(None, (base_name, group)))
value_map = extract_variables_from_log(
log_vars, subfieldnames, "controller", as_dict=True)
tab_data = {key.split(".", 2)[2]: value
tab_data = {key.split(".", 2)[-1]: value
for key, value in value_map.items()}

grid_spec: Tuple[Optional[int], Optional[int]] = (None, None)
Expand Down
10 changes: 5 additions & 5 deletions python/gym_jiminy/common/gym_jiminy/common/envs/locomotion.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class WalkerJiminyEnv(BaseJiminyEnv):
def __init__(self,
urdf_path: Optional[str],
hardware_path: Optional[str] = None,
mesh_path_dir: Optional[str] = None,
mesh_dir_path: Optional[str] = None,
simulation_duration_max: float = DEFAULT_SIMULATION_DURATION,
step_dt: float = DEFAULT_STEP_DT,
reward_mixture: Optional[dict] = None,
Expand All @@ -94,7 +94,7 @@ def __init__(self,
:param hardware_path: Path of Jiminy hardware description toml file.
Optional: Looking for '\*_hardware.toml' file in
the same folder and with the same name.
:param mesh_path_dir: Path to the folder containing the model meshes.
:param mesh_dir_path: Path to the folder containing the model meshes.
Optional: Env variable 'JIMINY_DATA_PATH' will be
used if available.
:param simulation_duration_max: Maximum duration of a simulation before
Expand Down Expand Up @@ -123,7 +123,7 @@ def __init__(self,
enables telemetry recording.
:param robot: Robot being simulated, already instantiated and
initialized. Build default robot using 'urdf_path',
'hardware_path' and 'mesh_path_dir' if omitted.
'hardware_path' and 'mesh_dir_path' if omitted.
Optional: None by default.
:param viewer_kwargs: Keyword arguments used to override the original
default values whenever a viewer is instantiated.
Expand Down Expand Up @@ -155,7 +155,7 @@ def __init__(self,
# Backup user arguments
self.reward_mixture = reward_mixture
self.urdf_path = urdf_path
self.mesh_path_dir = mesh_path_dir
self.mesh_dir_path = mesh_dir_path
self.hardware_path = hardware_path
self.config_path = config_path
self.std_ratio = std_ratio
Expand All @@ -174,7 +174,7 @@ def __init__(self,
simulator = Simulator.build(
urdf_path=self.urdf_path,
hardware_path=self.hardware_path,
mesh_path_dir=self.mesh_path_dir,
mesh_dir_path=self.mesh_dir_path,
config_path=self.config_path,
avoid_instable_collisions=self.avoid_instable_collisions,
debug=debug,
Expand Down
2 changes: 1 addition & 1 deletion python/gym_jiminy/envs/gym_jiminy/envs/anymal.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def __init__(self, debug: bool = False, **kwargs: Any) -> None:
# Initialize the walker environment
super().__init__(
urdf_path=urdf_path,
mesh_path_dir=data_dir,
mesh_dir_path=data_dir,
avoid_instable_collisions=True,
debug=debug,
**{**dict(
Expand Down
4 changes: 2 additions & 2 deletions python/gym_jiminy/envs/gym_jiminy/envs/atlas.py
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ def __init__(self, debug: bool = False, **kwargs: Any) -> None:
# Initialize the walker environment
super().__init__(
urdf_path=urdf_path,
mesh_path_dir=data_dir,
mesh_dir_path=data_dir,
avoid_instable_collisions=True,
debug=debug,
**{**dict(
Expand Down Expand Up @@ -220,7 +220,7 @@ def joint_position_index(joint_name: str) -> int:
super().__init__(
robot=robot,
urdf_path=urdf_path,
mesh_path_dir=data_dir,
mesh_dir_path=data_dir,
avoid_instable_collisions=True,
debug=debug,
**{**dict(
Expand Down
2 changes: 1 addition & 1 deletion python/gym_jiminy/envs/gym_jiminy/envs/cassie.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ def __init__(self, debug: bool = False, **kwargs: Any) -> None:
super().__init__(
robot=robot,
urdf_path=urdf_path,
mesh_path_dir=data_dir,
mesh_dir_path=data_dir,
avoid_instable_collisions=True,
debug=debug,
**{**dict(
Expand Down
2 changes: 1 addition & 1 deletion python/gym_jiminy/envs/gym_jiminy/envs/digit.py
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ def __init__(self, debug: bool = False, **kwargs: Any) -> None:
super().__init__(
robot=robot,
urdf_path=urdf_path,
mesh_path_dir=data_dir,
mesh_dir_path=data_dir,
avoid_instable_collisions=True,
debug=debug,
**{**dict(
Expand Down
8 changes: 5 additions & 3 deletions python/gym_jiminy/rllib/gym_jiminy/rllib/utilities.py
Original file line number Diff line number Diff line change
Expand Up @@ -897,9 +897,11 @@ def _sample_one_episode_and_collect_metrics(worker: EnvRunner) -> Tuple[
for env in worker.env.envs:
env.unwrapped.log_path = None

# Run a single episode and extract the path of the log file.
# Run a single episode.
# Note that episodes are sorted by environment indices by design.
episodes = worker.sample(num_episodes=1, random_actions=False)

# Extract the path of the log files
log_paths: Tuple[str, ...] = tuple(
filter(None, worker.env.get_attr('log_path')))

Expand Down Expand Up @@ -1218,8 +1220,8 @@ def evaluate_from_algo(algo: Algorithm,
_pretty_print_episode_metrics(all_episodes, step_dt)

# Backup only the log file corresponding to the best and worst trial
all_returns = np.array([
episode.get_return() for episode in all_episodes])
all_returns = [
episode.get_return() for episode in all_episodes]
idx_worst, idx_best = np.argsort(all_returns)[[0, -1]]
log_labels, log_paths = [], []
for label, idx in (
Expand Down
12 changes: 6 additions & 6 deletions python/jiminy_py/src/jiminy_py/dynamics.py
Original file line number Diff line number Diff line change
Expand Up @@ -648,30 +648,30 @@ def compute_transform_contact(
collision_model = robot.collision_model

# Compute the transform in the world of the contact points
contact_frames_transform = []
contact_frame_transforms = []
for frame_index in robot.contact_frame_indices:
transform = robot.pinocchio_data.oMf[frame_index]
contact_frames_transform.append(transform)
contact_frame_transforms.append(transform)

# Compute the transform of the ground at these points
if ground_profile is not None:
contact_ground_transform = []
ground_pos = np.zeros(3)
for frame_transform in contact_frames_transform:
for frame_transform in contact_frame_transforms:
ground_pos[2], normal = ground_profile(
frame_transform.translation[:2])
ground_rot = pin.Quaternion.FromTwoVectors(
np.array([0.0, 0.0, 1.0]), normal).matrix()
contact_ground_transform.append(pin.SE3(ground_rot, ground_pos))
else:
contact_ground_transform = [
pin.SE3.Identity() for _ in contact_frames_transform]
pin.SE3.Identity() for _ in contact_frame_transforms]

# Compute the position and normal of the contact points wrt their
# respective ground transform.
contact_frames_pos_rel = []
for frame_transform, ground_transform in \
zip(contact_frames_transform, contact_ground_transform):
zip(contact_frame_transforms, contact_ground_transform):
transform_rel = ground_transform.actInv(frame_transform)
contact_frames_pos_rel.append(transform_rel.translation)

Expand Down Expand Up @@ -707,7 +707,7 @@ def compute_transform_contact(
rot_offset = pin.Quaternion.FromTwoVectors(
normal_offset, np.array([0.0, 0.0, 1.0])).matrix()
if contact_frames_pos_rel:
contact_frame_pos = contact_frames_transform[
contact_frame_pos = contact_frame_transforms[
contact_frames_order[0]].translation
pos_shift = (
rot_offset @ contact_frame_pos)[2] - contact_frame_pos[2]
Expand Down
12 changes: 6 additions & 6 deletions python/jiminy_py/src/jiminy_py/log.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ def extract_variables_from_log(log_vars: Dict[str, np.ndarray],

def build_robot_from_log(
log_data: Dict[str, Any],
mesh_path_dir: Optional[str] = None,
mesh_dir_path: Optional[str] = None,
mesh_package_dirs: Sequence[str] = (),
*, robot_name: Optional[str] = None
) -> jiminy.Robot:
Expand All @@ -107,7 +107,7 @@ def build_robot_from_log(
the name for each of them.
:param log_data: Logged data (constants plus variables) as a dictionary.
:param mesh_path_dir: Overwrite the common root of all absolute mesh paths.
:param mesh_dir_path: Overwrite the common root of all absolute mesh paths.
It may be necessary to read logs generated on
different environments.
:param mesh_package_dirs: Prepend custom mesh package search path
Expand Down Expand Up @@ -144,12 +144,12 @@ def build_robot_from_log(

# Load robot from binary data
return jiminy.load_from_binary(
robot_data, mesh_path_dir, mesh_package_dirs)
robot_data, mesh_dir_path, mesh_package_dirs)


def build_robots_from_log(
log_data: Dict[str, Any],
mesh_path_dir: Optional[str] = None,
mesh_dir_path: Optional[str] = None,
mesh_package_dirs: Sequence[str] = (),
) -> Sequence[jiminy.Robot]:
"""Build all the robots in the log of the simulation.
Expand All @@ -159,7 +159,7 @@ def build_robots_from_log(
available robot. Refer to `build_robot_from_log` for more information.
:param log_data: Logged data (constants and variables) as a dictionary.
:param mesh_path_dir: Overwrite the common root of all absolute mesh paths.
:param mesh_dir_path: Overwrite the common root of all absolute mesh paths.
It which may be necessary to read log generated on a
different environment.
:param mesh_package_dirs: Prepend custom mesh package search path
Expand All @@ -180,7 +180,7 @@ def build_robots_from_log(
robots = []
for robot_name in robot_names:
robot = build_robot_from_log(
log_data, mesh_path_dir, mesh_package_dirs, robot_name=robot_name)
log_data, mesh_dir_path, mesh_package_dirs, robot_name=robot_name)
robots.append(robot)

return robots
Expand Down
Loading

0 comments on commit 0373511

Please sign in to comment.