Codebase for the "Adversarial Motion Priors Make Good Substitutes for Complex Reward Functions" project. This repository contains the code necessary to ground agent skills using small amounts of reference data (4.5 seconds). All experiments are performed using the A1 robot from Unitree. This repository is based off of Nikita Rudin's legged_gym repo, and enables us to train policies using Isaac Gym.
Maintainer: Alejandro Escontrela Affiliation: University of California at Berkeley Contact: escontrela@berkeley.edu
Project website: https://bit.ly/3hpvbD6 Paper: https://drive.google.com/file/d/1kFm79nMmrc0ZIiH0XO8_HV-fj73agheO/view?usp=sharing
conda create -n amp_hw python==3.8
conda activate amp_hw
pip3 install torch==1.10.0+cu113 torchvision==0.11.1+cu113 tensorboard==2.8.0 pybullet==3.2.1 opencv-python==4.5.5.64 torchaudio==0.10.0+cu113 -f https://download.pytorch.org/whl/cu113/torch_stable.html
cd isaacgym/python && pip install -e .
cd examples && python 1080_balls_of_solitude.py
isaacgym/docs/index.html
)cd AMP_for_hardware/rsl_rl && pip install -e .
cd ../ && pip install -e .
legged_robot.py
) and a config file (legged_robot_config.py
). The config file contains two classes: one conatianing all the environment parameters (LeggedRobotCfg
) and one for the training parameters (LeggedRobotCfgPPo
). cfg
will add a function with a corresponding name to the list of elements which will be summed to get the total reward. The AMP reward parameters are defined in LeggedRobotCfgPPO
, as well as the path to the reference data.task_registry.register(name, EnvClass, EnvConfig, TrainConfig)
. This is done in envs/__init__.py
, but can also be done from outside of this repository.datasets
folder.`python legged_gym/scripts/train.py --task=a1_amp
--sim_device=cpu
, --rl_device=cpu
(sim on CPU and rl on GPU is possible).--headless
.v
to stop the rendering. You can then enable it later to check the progress.AMP_for_hardware/logs/<experiment_name>/<date_time>_<run_name>/model_<iteration>.pt
. Where <experiment_name>
and <run_name>
are defined in the train config.python legged_gym/scripts/play.py --task=a1_amp
load_run
and checkpoint
in the train config.python legged_gym/scripts/record_policy.py --task=a1_amp
The base environment legged_robot
implements a rough terrain locomotion task. The corresponding cfg does not specify a robot asset (URDF/ MJCF) and no reward scales.
envs/
with '<your_env>_config.py
, which inherit from an existing environment cfgs resourses/
.cfg
set the asset path, define body names, default_joint_positions and PD gains. Specify the desired train_cfg
and the name of the environment (python class).train_cfg
set experiment_name
and run_name
isaacgym_anymal/envs/__init__.py
.cfg
, cfg_train
as needed. To remove a reward set its scale to zero. Do not modify parameters of other envs!ImportError: libpython3.8m.so.1.0: cannot open shared object file: No such file or directory
, do: sudo apt install libpython3.8
The contact forces reported by net_contact_force_tensor
are unreliable when simulating on GPU with a triangle mesh terrain. A workaround is to use force sensors, but the force are propagated through the sensors of consecutive bodies resulting in an undesireable behaviour. However, for a legged robot it is possible to add sensors to the feet/end effector only and get the expected results. When using the force sensors make sure to exclude gravity from trhe reported forces with sensor_options.enable_forward_dynamics_forces
. Example:
sensor_pose = gymapi.Transform()
for name in feet_names:
sensor_options = gymapi.ForceSensorProperties()
sensor_options.enable_forward_dynamics_forces = False # for example gravity
sensor_options.enable_constraint_solver_forces = True # for example contacts
sensor_options.use_world_frame = True # report forces in world frame (easier to get vertical components)
index = self.gym.find_asset_rigid_body_index(robot_asset, name)
self.gym.create_asset_force_sensor(robot_asset, index, sensor_pose, sensor_options)
(...)
sensor_tensor = self.gym.acquire_force_sensor_tensor(self.sim)
self.gym.refresh_force_sensor_tensor(self.sim)
force_sensor_readings = gymtorch.wrap_tensor(sensor_tensor)
self.sensor_forces = force_sensor_readings.view(self.num_envs, 4, 6)[..., :3]
(...)
self.gym.refresh_force_sensor_tensor(self.sim)
contact = self.sensor_forces[:, :, 2] > 1.