Skip to content

Commit

Permalink
continuous integration
Browse files Browse the repository at this point in the history
  • Loading branch information
codekansas committed May 15, 2024
1 parent 82dc6ba commit 2322e65
Show file tree
Hide file tree
Showing 5 changed files with 161 additions and 10 deletions.
61 changes: 61 additions & 0 deletions .github/workflows/update_stompy_s3.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
name: Update Stompy S3 Model

on:
release:
types: [created]
schedule:
- cron: "0 0 * * *"
workflow_dispatch:

permissions:
contents: read
id-token: write

concurrency:
group: "stompy-s3-model"
cancel-in-progress: true

jobs:
publish:
timeout-minutes: 10
name: Update Stompy S3 Model

# We don't need to run on all platforms since this package is
# platform-agnostic. The output wheel is something like
# "monotonic_attention-<version>-py3-none-any.whl".
runs-on: ubuntu-latest

steps:
- name: Checkout code
uses: actions/checkout@v3

- name: Set up Python
uses: actions/setup-python@v4
with:
python-version: "3.10"

- name: Install dependencies
run: |
pip install kscale-onshape-library '.'
- name: Build package
env:
ONSHAPE_ACCESS_KEY: ${{ secrets.ONSHAPE_ACCESS_KEY }}
ONSHAPE_SECRET_KEY: ${{ secrets.ONSHAPE_SECRET_KEY }}
ONSHAPE_API: ${{ secrets.ONSHAPE_API }}
run: python -m sim.scripts.update_stompy_s3

- name: Configure AWS credentials
uses: aws-actions/configure-aws-credentials@v1
with:
aws-access-key-id: ${{ secrets.AWS_ACCESS_KEY_ID }}
aws-secret-access-key: ${{ secrets.AWS_SECRET_ACCESS_KEY }}
aws-region: us-east-1

- name: Upload to S3
env:
AWS_S3_BUCKET: ${{ secrets.AWS_S3_BUCKET }}
run: |
for file in stompy/*.tar.gz; do
aws s3 cp "$file" s3://${AWS_S3_BUCKET}/$(basename "$file")
done
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -25,4 +25,4 @@ out*/
# Training artifacts
wandb/
runs/
stompy/
stompy/
23 changes: 15 additions & 8 deletions sim/humanoid_gym/play.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""Script to replay a trained policy in the environment."""

import argparse
import logging
import os
from datetime import datetime

Expand All @@ -9,11 +10,17 @@
from isaacgym import gymapi
from tqdm import tqdm

from sim.logging import configure_logging

logger = logging.getLogger(__name__)

from sim.env import run_dir
from sim.humanoid_gym.envs import * # noqa: F403


def play(args: argparse.Namespace) -> None:
configure_logging()

env_cfg, train_cfg = task_registry.get_cfgs(name=args.task)
# override some parameters for testing
env_cfg.env.num_envs = min(env_cfg.env.num_envs, 1)
Expand All @@ -31,7 +38,7 @@ def play(args: argparse.Namespace) -> None:
env_cfg.noise.noise_level = 0.5

train_cfg.seed = 123145
print("train_cfg.runner_class_name:", train_cfg.runner_class_name)
logger.info("train_cfg.runner_class_name: %s", train_cfg.runner_class_name)

# prepare environment
env, _ = task_registry.make_env(name=args.task, args=args, env_cfg=env_cfg)
Expand All @@ -44,7 +51,7 @@ def play(args: argparse.Namespace) -> None:
ppo_runner, train_cfg = task_registry.make_alg_runner(env=env, name=args.task, args=args, train_cfg=train_cfg)
policy = ppo_runner.get_inference_policy(device=env.device)

logger = Logger(env.dt)
env_logger = Logger(env.dt)
robot_index = 0 # which robot is used for logging
joint_index = 1 # which joint is used for logging
stop_state_log = 1200 # number of steps before plotting states
Expand All @@ -58,8 +65,8 @@ def play(args: argparse.Namespace) -> None:
camera_rotation = gymapi.Quat.from_axis_angle(gymapi.Vec3(-0.3, 0.2, 1), np.deg2rad(135))
actor_handle = env.gym.get_actor_handle(env.envs[0], 0)
body_handle = env.gym.get_actor_rigid_body_handle(env.envs[0], actor_handle, 0)
print(body_handle)
print(actor_handle)
logger.info("body_handle: %s", body_handle)
logger.info("actor_handle: %s", actor_handle)
env.gym.attach_camera_to_body(
h1, env.envs[0], body_handle, gymapi.Transform(camera_offset, camera_rotation), gymapi.FOLLOW_POSITION
)
Expand Down Expand Up @@ -99,7 +106,7 @@ def play(args: argparse.Namespace) -> None:

video.write(img[..., :3]) # Write only the RGB channels

logger.log_states(
env_logger.log_states(
{
"dof_pos_target": actions[robot_index, joint_index].item() * env.cfg.control.action_scale,
"dof_pos": env.dof_pos[robot_index, joint_index].item(),
Expand All @@ -119,10 +126,10 @@ def play(args: argparse.Namespace) -> None:
if infos["episode"]:
num_episodes = env.reset_buf.sum().item()
if num_episodes > 0:
logger.log_rewards(infos["episode"], num_episodes)
env_logger.log_rewards(infos["episode"], num_episodes)

logger.print_rewards()
logger.plot_states()
env_logger.print_rewards()
env_logger.plot_states()

if RENDER:
video.release()
Expand Down
2 changes: 1 addition & 1 deletion sim/scripts/print_joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ def main() -> None:

# Makes a "tree" of the joints using common prefixes.
joint_names.sort()
joint_tree = {}
joint_tree: Dict = {}
for joint_name in joint_names:
parts = joint_name.split("_")
current_tree = joint_tree
Expand Down
83 changes: 83 additions & 0 deletions sim/scripts/update_stompy_s3.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
"""Updates the Stompy model."""

import tarfile
from pathlib import Path

from kol.logging import configure_logging
from kol.onshape.converter import Converter

STOMPY_MODEL = (
"https://cad.onshape.com/documents/71f793a23ab7562fb9dec82d/"
"w/6160a4f44eb6113d3fa116cd/e/1a95e260677a2d2d5a3b1eb3"
)

SUFFIX_TO_JOINT_EFFORT = {
"dof_x4_h": 1.5,
"dof_x4": 1.5,
"dof_x6": 3,
"dof_x8": 6,
"dof_x10": 12,
"knee_revolute": 13.9,
"ankle_revolute": 6,
}


def main() -> None:
configure_logging()

output_dir = Path("stompy")

# Gets the latest STL URDF.
converter = Converter(
document_url=STOMPY_MODEL,
output_dir=output_dir / "latest_stl_urdf",
suffix_to_joint_effort=list(SUFFIX_TO_JOINT_EFFORT.items()),
disable_mimics=True,
mesh_ext="stl",
)
converter.save_urdf()
latest_stl_urdf_path = converter.output_dir

# Manually builds the tarball.
with tarfile.open(output_dir / "latest_stl_urdf.tar.gz", "w:gz") as tar:
for suffix in (".urdf", ".stl"):
for file in latest_stl_urdf_path.rglob(f"**/*{suffix}"):
tar.add(file, arcname=file.relative_to(latest_stl_urdf_path))

# Gets the latest OBJ URDF.
converter = Converter(
document_url=STOMPY_MODEL,
output_dir=output_dir / "latest_obj_urdf",
suffix_to_joint_effort=list(SUFFIX_TO_JOINT_EFFORT.items()),
disable_mimics=True,
mesh_ext="obj",
)
converter.save_urdf()
latest_obj_urdf_path = converter.output_dir

# Manually builds the tarball.
with tarfile.open(output_dir / "latest_obj_urdf.tar.gz", "w:gz") as tar:
for suffix in (".urdf", ".obj"):
for file in latest_obj_urdf_path.rglob(f"**/*{suffix}"):
tar.add(file, arcname=file.relative_to(latest_obj_urdf_path))

# Gets the latest MJCF.
converter = Converter(
document_url=STOMPY_MODEL,
output_dir=output_dir / "latest_mjcf",
suffix_to_joint_effort=list(SUFFIX_TO_JOINT_EFFORT.items()),
disable_mimics=True,
)
converter.save_mjcf()
latest_mjcf_path = converter.output_dir

# Manually builds the tarball.
with tarfile.open(output_dir / "latest_mjcf.tar.gz", "w:gz") as tar:
for suffix in (".xml", ".stl"):
for file in latest_mjcf_path.rglob(f"**/*{suffix}"):
tar.add(file, arcname=file.relative_to(latest_mjcf_path))


if __name__ == "__main__":
# python -m sim.scripts.update_stompy
main()

0 comments on commit 2322e65

Please sign in to comment.