Skip to content

Commit

Permalink
Merge pull request #13 from abizovnuralem/added_g1
Browse files Browse the repository at this point in the history
removed the hardcode and add G1 support
  • Loading branch information
abizovnuralem authored Jun 5, 2024
2 parents ca64a17 + 79fb638 commit 3f66281
Show file tree
Hide file tree
Showing 18 changed files with 1,689 additions and 102 deletions.
16 changes: 15 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,13 @@ Real time Go2 Balancing:
</p>


Real time G1 Balancing:

<p align="center">
<img width="1280" height="600" src="https://github.com/abizovnuralem/go2_omniverse/assets/33475993/d035f72a-8996-461c-a902-38e68052d029" alt='Go2'>
</p>


Go2 Ros2 Camera stream:

<p align="center">
Expand Down Expand Up @@ -72,6 +79,7 @@ VR support:
9. Nav2 with Slam_toolbox :white_check_mark:
10. Bunch of RL-envs for custom dog training :white_check_mark:
11. Custom numbers of robots :white_check_mark:
12. Added G1 Unitree support :white_check_mark:

## Your feedback and support mean the world to us.

Expand Down Expand Up @@ -127,12 +135,18 @@ with Isaac_sim/extension.toml in this repo.

## Usage
The current project was tested on Ubuntu 22.04, IsaacSim 4.0 with Isaac Lab and Nvidia Driver Version: 545.
To start the project, execute:
To start the project with Unitree GO2, execute:

```
./run_sim.sh
```

To start the project with Unitree G1, execute:

```
./run_sim_g1.sh
```

You can control the dog using "WASD" keyboard commands

## ROS2 SDK
Expand Down
40 changes: 40 additions & 0 deletions agent_cfg.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,4 +59,44 @@
'resume': False,
'load_run': '.*',
'load_checkpoint': 'model_.*.pt'
}


unitree_g1_agent_cfg = {
'seed': 42,
'device': 'cuda',
'num_steps_per_env': 24,
'max_iterations': 15000,
'empirical_normalization': False,
'policy': {
'class_name': 'ActorCritic',
'init_noise_std': 1.0,
'actor_hidden_dims': [512, 256, 128],
'critic_hidden_dims': [512, 256, 128],
'activation': 'elu'
},
'algorithm': {
'class_name': 'PPO',
'value_loss_coef': 1.0,
'use_clipped_value_loss': True,
'clip_param': 0.2,
'entropy_coef': 0.01,
'num_learning_epochs': 5,
'num_mini_batches': 4,
'learning_rate': 0.001,
'schedule': 'adaptive',
'gamma': 0.99,
'lam': 0.95,
'desired_kl': 0.01,
'max_grad_norm': 1.0
},
'save_interval': 50,
'experiment_name': 'g1_rough',
'run_name': '',
'logger': 'tensorboard',
'neptune_project': 'orbit',
'wandb_project': 'orbit',
'resume': False,
'load_run': '.*',
'load_checkpoint': 'model_.*.pt'
}
24 changes: 23 additions & 1 deletion custom_rl_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,9 @@
import omni.isaac.lab_tasks.manager_based.locomotion.velocity.mdp as mdp


from robots.g1.config import G1_CFG


base_command = []


Expand Down Expand Up @@ -298,4 +301,23 @@ def __post_init__(self):
self.rewards.dof_acc_l2.weight = -2.5e-7

# terminations
self.terminations.base_contact.params["sensor_cfg"].body_names = "base"
self.terminations.base_contact.params["sensor_cfg"].body_names = "base"


@configclass
class G1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# Scene
G1_MINIMAL_CFG = G1_CFG.copy()
G1_MINIMAL_CFG.spawn.usd_path = "./robots/g1/g1.usd"
self.scene.robot = G1_MINIMAL_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_link"

# rewards
self.rewards.feet_air_time.params["sensor_cfg"].body_names = ".*_ankle_roll_link"
self.rewards.undesired_contacts = None

# Terminations
self.terminations.base_contact.params["sensor_cfg"].body_names = ["torso_link"]
Binary file not shown.
Binary file not shown.
Binary file not shown.
241 changes: 241 additions & 0 deletions logs/rsl_rl/g1_rough/2024-06-03_21-09-07/git/IsaacLab.diff
Original file line number Diff line number Diff line change
@@ -0,0 +1,241 @@
--- git status ---
On branch main
Your branch is up to date with 'origin/main'.

Changes not staged for commit:
(use "git add <file>..." to update what will be committed)
(use "git restore <file>..." to discard changes in working directory)
modified: source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py
modified: source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/mdp/rewards.py
modified: source/standalone/workflows/rsl_rl/train.py

Untracked files:
(use "git add <file>..." to include in what will be committed)
source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/
source/exts/

no changes added to commit (use "git add" and/or "git commit -a")


--- git diff ---
diff --git a/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py b/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py
index 8533010..43f55b2 100644
--- a/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py
+++ b/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py
@@ -265,3 +265,160 @@ H1_MINIMAL_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1/h1_mi

This configuration removes most collision meshes to speed up simulation.
"""
+
+
+
+G1_CFG = ArticulationCfg(
+ spawn=sim_utils.UsdFileCfg(
+ usd_path="/home/brimo/Desktop/g1/g1_t.usd",
+ activate_contact_sensors=True,
+ rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ disable_gravity=False,
+ retain_accelerations=False,
+ linear_damping=0.0,
+ angular_damping=0.0,
+ max_linear_velocity=1000.0,
+ max_angular_velocity=1000.0,
+ max_depenetration_velocity=1.0,
+ ),
+ articulation_props=sim_utils.ArticulationRootPropertiesCfg(
+ enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=4
+ ),
+ ),
+ init_state=ArticulationCfg.InitialStateCfg(
+ pos=(0.0, 0.0, 0.70),
+ joint_pos={
+
+ ".*_hip_pitch_joint": -0.28,
+ ".*_knee_joint": 0.63,
+ ".*_ankle_pitch_joint": -0.35,
+
+ ".*_elbow_pitch_joint": 0.87,
+ "left_shoulder_roll_joint": 0.16,
+ "left_shoulder_pitch_joint": 0.35,
+
+ "right_shoulder_roll_joint": -0.16,
+ "right_shoulder_pitch_joint": 0.35,
+
+ "left_one_joint": 1.0,
+ "right_one_joint": -1.0,
+
+
+ },
+ joint_vel={".*": 0.0},
+ ),
+ soft_joint_pos_limit_factor=0.9,
+ actuators={
+ "legs": ImplicitActuatorCfg(
+ joint_names_expr=[
+ ".*_hip_yaw_joint",
+ ".*_hip_roll_joint",
+ ".*_hip_pitch_joint",
+ ".*_knee_joint",
+ "torso_joint"
+ ],
+ effort_limit=300,
+ velocity_limit=100.0,
+ stiffness={
+ ".*_hip_yaw_joint": 150.0,
+ ".*_hip_roll_joint": 150.0,
+ ".*_hip_pitch_joint": 200.0,
+ ".*_knee_joint": 200.0,
+ "torso_joint": 200.0,
+ },
+ damping={
+ ".*_hip_yaw_joint": 5.0,
+ ".*_hip_roll_joint": 5.0,
+ ".*_hip_pitch_joint": 5.0,
+ ".*_knee_joint": 5.0,
+ "torso_joint": 5.0,
+ },
+ armature={
+ ".*_hip_yaw_joint": 0.1,
+ ".*_hip_roll_joint": 0.1,
+ ".*_hip_pitch_joint": 0.1,
+ ".*_knee_joint": 0.1,
+ "torso_joint": 0.1,
+ },
+ ),
+ "feet": ImplicitActuatorCfg(
+ joint_names_expr=[
+ ".*_ankle_pitch_joint",
+ ".*_ankle_roll_joint"
+ ],
+ stiffness={
+ ".*_ankle_pitch_joint": 20.0,
+ ".*_ankle_roll_joint": 20.0
+ },
+ damping={
+ ".*_ankle_pitch_joint": 4.0,
+ ".*_ankle_roll_joint": 4.0
+ },
+ armature={
+ ".*_ankle_pitch_joint": 0.1,
+ ".*_ankle_roll_joint": 0.1
+ },
+ ),
+ "arms": ImplicitActuatorCfg(
+ joint_names_expr=[
+ ".*_shoulder_pitch_joint",
+ ".*_shoulder_roll_joint",
+ ".*_shoulder_yaw_joint",
+ ".*_elbow_pitch_joint",
+ ".*_elbow_roll_joint",
+ ".*_five_joint",
+ ".*_three_joint",
+ ".*_six_joint",
+ ".*_four_joint",
+ ".*_zero_joint",
+ ".*_one_joint",
+ ".*_two_joint"
+ ],
+ effort_limit=300,
+ velocity_limit=100.0,
+ stiffness={
+ ".*_shoulder_pitch_joint": 40.0,
+ ".*_shoulder_roll_joint": 40.0,
+ ".*_shoulder_yaw_joint": 40.0,
+ ".*_elbow_pitch_joint": 40.0,
+ ".*_elbow_roll_joint": 40.0,
+ ".*_five_joint": 40.0,
+ ".*_three_joint": 40.0,
+ ".*_six_joint": 40.0,
+ ".*_four_joint": 40.0,
+ ".*_zero_joint": 40.0,
+ ".*_one_joint": 40.0,
+ ".*_two_joint": 40.0,
+ },
+ damping={
+ ".*_shoulder_pitch_joint": 10.0,
+ ".*_shoulder_roll_joint": 10.0,
+ ".*_shoulder_yaw_joint": 10.0,
+ ".*_elbow_pitch_joint": 10.0,
+ ".*_elbow_roll_joint": 10.0,
+ ".*_five_joint": 10.0,
+ ".*_three_joint": 10.0,
+ ".*_six_joint": 10.0,
+ ".*_four_joint": 10.0,
+ ".*_zero_joint": 10.0,
+ ".*_one_joint": 10.0,
+ ".*_two_joint": 10.0,
+ },
+ armature={
+ ".*_shoulder_pitch_joint": 0.1,
+ ".*_shoulder_roll_joint": 0.1,
+ ".*_shoulder_yaw_joint": 0.1,
+ ".*_elbow_pitch_joint": 0.1,
+ ".*_elbow_roll_joint": 0.1,
+ ".*_five_joint": 0.1,
+ ".*_three_joint": 0.1,
+ ".*_six_joint": 0.1,
+ ".*_four_joint": 0.1,
+ ".*_zero_joint": 0.1,
+ ".*_one_joint": 0.1,
+ ".*_two_joint": 0.1,
+ },
+ ),
+ },
+)
+"""Configuration for the Unitree G1 Humanoid robot."""
diff --git a/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/mdp/rewards.py b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/mdp/rewards.py
index b3a1756..96d2612 100644
--- a/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/mdp/rewards.py
+++ b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/mdp/rewards.py
@@ -47,6 +47,7 @@ def feet_air_time_positive_biped(env, command_name: str, threshold: float, senso
If the commands are small (i.e. the agent is not supposed to take a step), then the reward is zero.
"""
contact_sensor: ContactSensor = env.scene.sensors[sensor_cfg.name]
+
# compute the reward
air_time = contact_sensor.data.current_air_time[:, sensor_cfg.body_ids]
contact_time = contact_sensor.data.current_contact_time[:, sensor_cfg.body_ids]
@@ -60,6 +61,28 @@ def feet_air_time_positive_biped(env, command_name: str, threshold: float, senso
return reward


+def feet_leave_ground(env, sensor_cfg: SceneEntityCfg, threshold: float) -> torch.Tensor:
+ """
+ Terminate if the robot's feet have left the ground.
+
+ Args:
+ env: The environment containing the sensors.
+ threshold (float): The threshold below which a contact force is considered as the feet having left the ground.
+ sensor_cfg (SceneEntityCfg): Configuration for the contact sensor.
+
+ Returns:
+ torch.Tensor: A tensor indicating whether the feet have left the ground for each instance.
+ """
+ contact_sensor = env.scene.sensors[sensor_cfg.name]
+ contact_forces = contact_sensor.data.net_forces_w[:, sensor_cfg.body_ids].norm(dim=-1)
+
+ # Check if contact forces are below the threshold
+ feet_off_ground = torch.all(contact_forces < threshold, dim=1)
+
+ return feet_off_ground
+
+
+
def feet_slide(env, sensor_cfg: SceneEntityCfg, asset_cfg: SceneEntityCfg = SceneEntityCfg("robot")) -> torch.Tensor:
# Penalize feet sliding
contact_sensor: ContactSensor = env.scene.sensors[sensor_cfg.name]
diff --git a/source/standalone/workflows/rsl_rl/train.py b/source/standalone/workflows/rsl_rl/train.py
index 748d9bd..d351b2a 100644
--- a/source/standalone/workflows/rsl_rl/train.py
+++ b/source/standalone/workflows/rsl_rl/train.py
@@ -24,8 +24,8 @@ parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU p
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
-parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
-parser.add_argument("--task", type=str, default=None, help="Name of the task.")
+parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.")
+parser.add_argument("--task", type=str, default="Isaac-Velocity-Rough-G1-v0", help="Name of the task.")
parser.add_argument("--seed", type=int, default=None, help="Seed used for the environment")
parser.add_argument("--max_iterations", type=int, default=None, help="RL Policy training iterations.")
# append RSL-RL cli arguments
Binary file not shown.
Binary file not shown.
Loading

0 comments on commit 3f66281

Please sign in to comment.