diff --git a/sim/envs/__init__.py b/sim/envs/__init__.py
index 639853fc..13260f07 100755
--- a/sim/envs/__init__.py
+++ b/sim/envs/__init__.py
@@ -16,10 +16,10 @@
from sim.envs.humanoids.grp_config import GprCfg, GprCfgPPO, GprStandingCfg
from sim.envs.humanoids.h1_config import H1Cfg, H1CfgPPO
from sim.envs.humanoids.h1_env import H1FreeEnv
-from sim.envs.humanoids.stompymicro_config import StompyMicroCfg, StompyMicroCfgPPO
-from sim.envs.humanoids.stompymicro_env import StompyMicroEnv
from sim.envs.humanoids.xbot_config import XBotCfg, XBotCfgPPO
from sim.envs.humanoids.xbot_env import XBotLFreeEnv
+from sim.envs.humanoids.zeroth_config import ZerothCfg, ZerothCfgPPO
+from sim.envs.humanoids.zeroth_env import ZerothEnv
from sim.utils.task_registry import TaskRegistry # noqa: E402
task_registry = TaskRegistry()
@@ -29,4 +29,4 @@
task_registry.register("h1", H1FreeEnv, H1Cfg(), H1CfgPPO())
task_registry.register("g1", G1FreeEnv, G1Cfg(), G1CfgPPO())
task_registry.register("XBotL_free", XBotLFreeEnv, XBotCfg(), XBotCfgPPO())
-task_registry.register("stompymicro", StompyMicroEnv, StompyMicroCfg(), StompyMicroCfgPPO())
+task_registry.register("zeroth", ZerothEnv, ZerothCfg(), ZerothCfgPPO())
diff --git a/sim/envs/humanoids/stompymicro_config.py b/sim/envs/humanoids/zeroth_config.py
similarity index 85%
rename from sim/envs/humanoids/stompymicro_config.py
rename to sim/envs/humanoids/zeroth_config.py
index 4189afda..7926cef5 100644
--- a/sim/envs/humanoids/stompymicro_config.py
+++ b/sim/envs/humanoids/zeroth_config.py
@@ -5,12 +5,12 @@
LeggedRobotCfg,
LeggedRobotCfgPPO,
)
-from sim.resources.stompymicro.joints import Robot
+from sim.resources.zeroth.joints import Robot
NUM_JOINTS = len(Robot.all_joints()) # 20
-class StompyMicroCfg(LeggedRobotCfg):
+class ZerothCfg(LeggedRobotCfg):
"""Configuration class for the Legs humanoid robot."""
class env(LeggedRobotCfg.env):
@@ -34,11 +34,11 @@ class safety:
terminate_after_contacts_on = []
class asset(LeggedRobotCfg.asset):
- name = "stompymicro"
+ name = "zeroth"
file = str(robot_urdf_path(name))
- foot_name = ["foot_left", "foot_right"]
- knee_name = ["ankle_pitch_left", "ankle_pitch_right"]
+ foot_name = ["foot_bracket_for_5dof_leg_v9", "foot_bracket_for_5dof_leg_v9_2"]
+ knee_name = ["leg_top_bracket_v8_1", "leg_top_bracket_v8_1_2"]
termination_height = 0.05
default_feet_height = 0.01
@@ -97,7 +97,7 @@ class control(LeggedRobotCfg.control):
# action scale: target angle = actionScale * action + defaultAngle
action_scale = 0.25
# decimation: Number of control action updates @ sim DT per policy DT
- decimation = 20 # 100hz
+ decimation = 10 # 100hz
class sim(LeggedRobotCfg.sim):
dt = 0.001 # 1000 Hz
@@ -123,7 +123,7 @@ class domain_rand(LeggedRobotCfg.domain_rand):
randomize_friction = True
friction_range = [0.1, 2.0]
randomize_base_mass = True # True
- added_mass_range = [-0.5, 0.5]
+ added_mass_range = [-0.25, 0.25]
push_robots = True # True
push_interval_s = 4
max_push_vel_xy = 0.05
@@ -157,30 +157,25 @@ class rewards:
only_positive_rewards = True
# tracking reward = exp(error*sigma)
tracking_sigma = 5.0
- max_contact_force = 50 # forces above this value are penalized
+ max_contact_force = 400 # forces above this value are penalized
class scales:
-
- # TODO: add an argument
- walking = False
-
- if walking == True:
- # reference motion tracking
- joint_pos = 1.6
- feet_clearance = 1.2
- feet_contact_number = 1.2
- feet_air_time = 1.2
- foot_slip = -0.05
- feet_distance = 0.2
- knee_distance = 0.2
- # contact
- feet_contact_forces = -0.01
- # vel tracking
- tracking_lin_vel = 1.2
- tracking_ang_vel = 1.1
- vel_mismatch_exp = 0.5 # lin_z; ang x,y
- low_speed = 0.4
- track_vel_hard = 0.5
+ # reference motion tracking
+ joint_pos = 1.6
+ feet_clearance = 1.2
+ feet_contact_number = 1.2
+ feet_air_time = 1.2
+ foot_slip = -0.05
+ feet_distance = 0.2
+ knee_distance = 0.2
+ # contact
+ feet_contact_forces = -0.01
+ # vel tracking
+ tracking_lin_vel = 1.2
+ tracking_ang_vel = 1.1
+ vel_mismatch_exp = 0.5 # lin_z; ang x,y
+ low_speed = 0.4
+ track_vel_hard = 0.5
# base pos
default_joint_pos = 1.0
@@ -212,7 +207,7 @@ class viewer:
lookat = [0, -2, 0]
-class StompyMicroCfgPPO(LeggedRobotCfgPPO):
+class ZerothCfgPPO(LeggedRobotCfgPPO):
seed = 5
runner_class_name = "OnPolicyRunner" # DWLOnPolicyRunner
@@ -237,7 +232,7 @@ class runner:
# logging
save_interval = 300 # check for potential saves every this many iterations
- experiment_name = "StompyMicro"
+ experiment_name = "zeroth"
run_name = ""
# load and resume
resume = False
diff --git a/sim/envs/humanoids/stompymicro_env.py b/sim/envs/humanoids/zeroth_env.py
similarity index 99%
rename from sim/envs/humanoids/stompymicro_env.py
rename to sim/envs/humanoids/zeroth_env.py
index 79669b50..c65c9e20 100644
--- a/sim/envs/humanoids/stompymicro_env.py
+++ b/sim/envs/humanoids/zeroth_env.py
@@ -2,7 +2,7 @@
"""Defines the environment for training the humanoid."""
from sim.envs.base.legged_robot import LeggedRobot
-from sim.resources.stompymicro.joints import Robot
+from sim.resources.zeroth.joints import Robot
from sim.utils.terrain import HumanoidTerrain
from isaacgym import gymtorch # isort:skip
@@ -12,8 +12,8 @@
import torch # isort:skip
-class StompyMicroEnv(LeggedRobot):
- """StompyFreeEnv is a class that represents a custom environment for a legged robot.
+class ZerothEnv(LeggedRobot):
+ """ZerothFreeEnv is a class that represents a custom environment for a legged robot.
Args:
cfg: Configuration object for the legged robot.
diff --git a/sim/resources/stompymicro/joints.py b/sim/resources/stompymicro/joints.py
deleted file mode 100644
index fb1e1551..00000000
--- a/sim/resources/stompymicro/joints.py
+++ /dev/null
@@ -1,280 +0,0 @@
-"""Defines a more Pythonic interface for specifying the joint names.
-
-The best way to re-generate this snippet for a new robot is to use the
-`sim/scripts/print_joints.py` script. This script will print out a hierarchical
-tree of the various joint names in the robot.
-"""
-
-import textwrap
-from abc import ABC
-from typing import Dict, List, Tuple, Union
-
-
-class Node(ABC):
- @classmethod
- def children(cls) -> List["Union[Node, str]"]:
- return [
- attr
- for attr in (getattr(cls, attr) for attr in dir(cls) if not attr.startswith("__"))
- if isinstance(attr, (Node, str))
- ]
-
- @classmethod
- def joints(cls) -> List[str]:
- return [
- attr
- for attr in (getattr(cls, attr) for attr in dir(cls) if not attr.startswith("__"))
- if isinstance(attr, str)
- ]
-
- @classmethod
- def joints_motors(cls) -> List[Tuple[str, str]]:
- joint_names: List[Tuple[str, str]] = []
- for attr in dir(cls):
- if not attr.startswith("__"):
- attr2 = getattr(cls, attr)
- if isinstance(attr2, str):
- joint_names.append((attr, attr2))
-
- return joint_names
-
- @classmethod
- def all_joints(cls) -> List[str]:
- leaves = cls.joints()
- for child in cls.children():
- if isinstance(child, Node):
- leaves.extend(child.all_joints())
- return leaves
-
- def __str__(self) -> str:
- parts = [str(child) for child in self.children()]
- parts_str = textwrap.indent("\n" + "\n".join(parts), " ")
- return f"[{self.__class__.__name__}]{parts_str}"
-
-
-class LeftArm(Node):
- shoulder_yaw = "left_shoulder_yaw"
- shoulder_pitch = "left_shoulder_pitch"
- elbow_pitch = "left_elbow_yaw" # FIXME: yaw vs pitch
-
-
-class RightArm(Node):
- shoulder_yaw = "right_shoulder_yaw"
- shoulder_pitch = "right_shoulder_pitch"
- elbow_pitch = "right_elbow_yaw" # FIXME: yaw vs pitch
-
-
-class LeftLeg(Node):
- hip_roll = "left_hip_roll"
- hip_yaw = "left_hip_yaw"
- hip_pitch = "left_hip_pitch"
- knee_pitch = "left_knee_pitch"
- ankle_pitch = "left_ankle_pitch"
-
-
-class RightLeg(Node):
- hip_roll = "right_hip_roll"
- hip_yaw = "right_hip_yaw"
- hip_pitch = "right_hip_pitch"
- knee_pitch = "right_knee_pitch"
- ankle_pitch = "right_ankle_pitch"
-
-
-class Legs(Node):
- left = LeftLeg()
- right = RightLeg()
-
-
-class Robot(Node):
- height = 0.31
- rotation = [0, 0, 0.707, 0.707]
-
- # left_arm = LeftArm()
- # right_arm = RightArm()
- legs = Legs()
-
- @classmethod
- def default_standing(cls) -> Dict[str, float]:
- return {
- # Legs
- cls.legs.left.hip_pitch: 0.0,
- cls.legs.left.hip_yaw: 0,
- cls.legs.left.hip_roll: 0,
- cls.legs.left.knee_pitch: 0,
- cls.legs.left.ankle_pitch: 0,
- cls.legs.right.hip_pitch: 0,
- cls.legs.right.hip_yaw: 0,
- cls.legs.right.hip_roll: 0,
- cls.legs.right.knee_pitch: 0,
- cls.legs.right.ankle_pitch: 0,
- # TODO: fixing this for debugging
- # Arms
- # cls.left_arm.shoulder_pitch: 0,
- # cls.left_arm.shoulder_yaw: 0,
- # cls.left_arm.elbow_pitch: 0,
- # cls.right_arm.shoulder_pitch: 0,
- # cls.right_arm.shoulder_yaw: 0,
- # cls.right_arm.elbow_pitch: 0,
- }
-
- @classmethod
- def default_limits(cls) -> Dict[str, Dict[str, float]]:
- return {
- # # left arm
- # Robot.left_arm.shoulder_pitch: {
- # "lower": -1.5707963,
- # "upper": 1.5707963,
- # },
- # Robot.left_arm.shoulder_yaw: {
- # "lower": -1.5707963,
- # "upper": 1.5707963,
- # },
- # Robot.left_arm.elbow_pitch: {
- # "lower": -1.2217305,
- # "upper": 1.2217305,
- # },
- # # right arm
- # Robot.right_arm.shoulder_pitch: {
- # "lower": -1.5707963,
- # "upper": 1.5707963,
- # },
- # Robot.right_arm.shoulder_yaw: {
- # "lower": -1.5707963,
- # "upper": 1.5707963,
- # },
- # Robot.right_arm.elbow_pitch: {
- # "lower": -1.2217305,
- # "upper": 1.2217305,
- # },
- # left leg
- Robot.legs.left.hip_pitch: {
- "lower": -1.5707963,
- "upper": 1.5707963,
- },
- Robot.legs.left.hip_yaw: {
- "lower": -1.5707963,
- "upper": 0.087266463,
- },
- Robot.legs.left.hip_roll: {
- "lower": -0.78539816,
- "upper": 0.78539816,
- },
- Robot.legs.left.knee_pitch: {
- "lower": 0,
- "upper": 1.0471976,
- },
- Robot.legs.left.ankle_pitch: {
- "lower": -1.0471976,
- "upper": 1.0471976,
- },
- # right leg
- Robot.legs.right.hip_pitch: {
- "lower": -1.5707963,
- "upper": 1.5707963,
- },
- Robot.legs.right.hip_yaw: {
- "lower": -0.087266463,
- "upper": 1.5707963,
- },
- Robot.legs.right.hip_roll: {
- "lower": -0.78539816,
- "upper": 0.78539816,
- },
- Robot.legs.right.knee_pitch: {
- "lower": -1.0471976,
- "upper": 0,
- },
- Robot.legs.right.ankle_pitch: {
- "lower": -1.0471976,
- "upper": 1.0471976,
- },
- }
-
- # p_gains
- @classmethod
- def stiffness(cls) -> Dict[str, float]:
- return {
- "hip_pitch": 5,
- "hip_yaw": 5,
- "hip_roll": 5,
- "knee_pitch": 5,
- "ankle_pitch": 5,
- # "shoulder_pitch": 5,
- # "shoulder_yaw": 5,
- # "shoulder_roll": 5,
- # "elbow_pitch": 5,
- # "elbow_yaw": 5,
- }
-
- # d_gains
- @classmethod
- def damping(cls) -> Dict[str, float]:
- return {
- "hip_pitch": 0.3,
- "hip_yaw": 0.3,
- "hip_roll": 0.3,
- "knee_pitch": 0.3,
- "ankle_pitch": 0.3,
- # "shoulder_pitch": 0.3,
- # "shoulder_yaw": 0.3,
- # "shoulder_roll": 0.3,
- # "elbow_pitch": 0.3,
- # "elbow_yaw": 0.3,
- }
-
- # pos_limits
- @classmethod
- def effort(cls) -> Dict[str, float]:
- return {
- "hip_pitch": 1,
- "hip_yaw": 1,
- "hip_roll": 1,
- "knee_pitch": 1,
- "ankle_pitch": 1,
- # "shoulder_pitch": 1,
- # "shoulder_yaw": 1,
- # "shoulder_roll": 1,
- # "elbow_pitch": 1,
- # "elbow_yaw": 1,
- }
-
- # vel_limits
- @classmethod
- def velocity(cls) -> Dict[str, float]:
- return {
- "hip_pitch": 10,
- "hip_yaw": 10,
- "hip_roll": 10,
- "knee_pitch": 10,
- "ankle_pitch": 10,
- # "shoulder_pitch": 10,
- # "shoulder_yaw": 10,
- # "shoulder_roll": 10,
- # "elbow_pitch": 10,
- # "elbow_yaw": 10,
- }
-
- @classmethod
- def friction(cls) -> Dict[str, float]:
- return {
- # pfb30 todo
- "hip_pitch": 0.05,
- "hip_yaw": 0.05,
- "hip_roll": 0.05,
- "knee_pitch": 0.05,
- "ankle_pitch": 0.05,
- # "ankle_pitch": 0.05,
- # "elbow_yaw": 0.05,
- # "elbow_pitch": 0.05,
- }
-
-
-def print_joints() -> None:
- joints = Robot.all_joints()
- assert len(joints) == len(set(joints)), "Duplicate joint names found!"
- print(Robot())
-
-
-if __name__ == "__main__":
- # python -m sim.Robot.joints
- print_joints()
diff --git a/sim/resources/stompymicro/robot.urdf b/sim/resources/stompymicro/robot.urdf
deleted file mode 100644
index a75c6b84..00000000
--- a/sim/resources/stompymicro/robot.urdf
+++ /dev/null
@@ -1,501 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/sim/resources/stompymicro/robot_calibration.xml b/sim/resources/stompymicro/robot_calibration.xml
deleted file mode 100644
index 199afdbf..00000000
--- a/sim/resources/stompymicro/robot_calibration.xml
+++ /dev/null
@@ -1,181 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/sim/resources/stompymicro/robot_fixed.urdf b/sim/resources/stompymicro/robot_fixed.urdf
deleted file mode 100644
index b4fc9eb5..00000000
--- a/sim/resources/stompymicro/robot_fixed.urdf
+++ /dev/null
@@ -1,500 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/sim/resources/stompymicro/robot_fixed.xml b/sim/resources/stompymicro/robot_fixed.xml
deleted file mode 100644
index b5436397..00000000
--- a/sim/resources/stompymicro/robot_fixed.xml
+++ /dev/null
@@ -1,177 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/sim/resources/stompymicro/__init__.py b/sim/resources/zeroth/__init__.py
similarity index 100%
rename from sim/resources/stompymicro/__init__.py
rename to sim/resources/zeroth/__init__.py
diff --git a/sim/resources/zeroth/joints.py b/sim/resources/zeroth/joints.py
new file mode 100644
index 00000000..890784f1
--- /dev/null
+++ b/sim/resources/zeroth/joints.py
@@ -0,0 +1,170 @@
+"""Defines a more Pythonic interface for specifying the joint names.
+
+The best way to re-generate this snippet for a new robot is to use the
+`sim/scripts/print_joints.py` script. This script will print out a hierarchical
+tree of the various joint names in the robot.
+"""
+
+import textwrap
+from abc import ABC
+from typing import Dict, List, Tuple, Union
+
+
+class Node(ABC):
+ @classmethod
+ def children(cls) -> List["Union[Node, str]"]:
+ return [
+ attr
+ for attr in (getattr(cls, attr) for attr in dir(cls) if not attr.startswith("__"))
+ if isinstance(attr, (Node, str))
+ ]
+
+ @classmethod
+ def joints(cls) -> List[str]:
+ return [
+ attr
+ for attr in (getattr(cls, attr) for attr in dir(cls) if not attr.startswith("__"))
+ if isinstance(attr, str)
+ ]
+
+ @classmethod
+ def joints_motors(cls) -> List[Tuple[str, str]]:
+ joint_names: List[Tuple[str, str]] = []
+ for attr in dir(cls):
+ if not attr.startswith("__"):
+ attr2 = getattr(cls, attr)
+ if isinstance(attr2, str):
+ joint_names.append((attr, attr2))
+
+ return joint_names
+
+ @classmethod
+ def all_joints(cls) -> List[str]:
+ leaves = cls.joints()
+ for child in cls.children():
+ if isinstance(child, Node):
+ leaves.extend(child.all_joints())
+ return leaves
+
+ def __str__(self) -> str:
+ parts = [str(child) for child in self.children()]
+ parts_str = textwrap.indent("\n" + "\n".join(parts), " ")
+ return f"[{self.__class__.__name__}]{parts_str}"
+
+
+class LeftLeg(Node):
+ hip_roll = "left_hip_roll"
+ hip_yaw = "left_hip_yaw"
+ hip_pitch = "left_hip_pitch"
+ knee_pitch = "left_knee_pitch"
+ ankle_pitch = "left_ankle_pitch"
+
+
+class RightLeg(Node):
+ hip_roll = "right_hip_roll"
+ hip_yaw = "right_hip_yaw"
+ hip_pitch = "right_hip_pitch"
+ knee_pitch = "right_knee_pitch"
+ ankle_pitch = "right_ankle_pitch"
+
+
+class Legs(Node):
+ left = LeftLeg()
+ right = RightLeg()
+
+
+class Robot(Node):
+ height = 0.34
+ rotation = [0, 0, 0, 1.0]
+
+ legs = Legs()
+
+ @classmethod
+ def default_standing(cls) -> Dict[str, float]:
+ return {
+ # Legs
+ cls.legs.left.hip_pitch: -0.267,
+ cls.legs.left.knee_pitch: -0.741,
+ cls.legs.left.hip_yaw: 0,
+ cls.legs.left.hip_roll: 0,
+ cls.legs.left.ankle_pitch: 0.581,
+ cls.legs.right.hip_pitch: -0.267,
+ cls.legs.right.knee_pitch: 0.741,
+ cls.legs.right.ankle_pitch: -0.581,
+ cls.legs.right.hip_yaw: 0,
+ cls.legs.right.hip_roll: 0,
+ }
+
+ @classmethod
+ def default_limits(cls) -> Dict[str, Dict[str, float]]:
+ return {
+ Robot.legs.left.knee_pitch: {
+ "lower": -1.57,
+ "upper": 0,
+ },
+ Robot.legs.right.knee_pitch: {
+ "lower": 0,
+ "upper": 1.57,
+ },
+ }
+
+ # p_gains
+ @classmethod
+ def stiffness(cls) -> Dict[str, float]:
+ return {
+ "hip_pitch": 17.681462808698132,
+ "hip_yaw": 17.681462808698132,
+ "hip_roll": 17.681462808698132,
+ "knee_pitch": 17.681462808698132,
+ "ankle_pitch": 17.681462808698132,
+ }
+
+ # d_gains
+ @classmethod
+ def damping(cls) -> Dict[str, float]:
+ return {
+ "hip_pitch": 0.5354656169048285,
+ "hip_yaw": 0.5354656169048285,
+ "hip_roll": 0.5354656169048285,
+ "knee_pitch": 0.5354656169048285,
+ "ankle_pitch": 0.5354656169048285,
+ }
+
+ # pos_limits
+ @classmethod
+ def effort(cls) -> Dict[str, float]:
+ return {
+ "hip_pitch": 10,
+ "hip_yaw": 10,
+ "hip_roll": 10,
+ "knee_pitch": 10,
+ "ankle_pitch": 10,
+ }
+
+ # vel_limits
+ @classmethod
+ def velocity(cls) -> Dict[str, float]:
+ return {
+ "hip_pitch": 10,
+ "hip_yaw": 10,
+ "hip_roll": 10,
+ "knee_pitch": 10,
+ "ankle_pitch": 10,
+ }
+
+ @classmethod
+ def friction(cls) -> Dict[str, float]:
+ return {
+ "ankle_pitch": 0.01,
+ }
+
+
+def print_joints() -> None:
+ joints = Robot.all_joints()
+ assert len(joints) == len(set(joints)), "Duplicate joint names found!"
+ print(Robot())
+
+
+if __name__ == "__main__":
+ # python -m sim.Robot.joints
+ print_joints()
diff --git a/sim/resources/zeroth/meshes/Part_76.stl b/sim/resources/zeroth/meshes/Part_76.stl
new file mode 100644
index 00000000..92f5aaa6
Binary files /dev/null and b/sim/resources/zeroth/meshes/Part_76.stl differ
diff --git a/sim/resources/zeroth/meshes/Robot_-_STS3250_v1.stl b/sim/resources/zeroth/meshes/Robot_-_STS3250_v1.stl
new file mode 100644
index 00000000..a2c01349
Binary files /dev/null and b/sim/resources/zeroth/meshes/Robot_-_STS3250_v1.stl differ
diff --git a/sim/resources/zeroth/meshes/Robot_-_STS3250_v1_2.stl b/sim/resources/zeroth/meshes/Robot_-_STS3250_v1_2.stl
new file mode 100644
index 00000000..29ab38b7
Binary files /dev/null and b/sim/resources/zeroth/meshes/Robot_-_STS3250_v1_2.stl differ
diff --git a/sim/resources/zeroth/meshes/Rotor.stl b/sim/resources/zeroth/meshes/Rotor.stl
new file mode 100644
index 00000000..9bd8fb9e
Binary files /dev/null and b/sim/resources/zeroth/meshes/Rotor.stl differ
diff --git a/sim/resources/zeroth/meshes/Rotor_2.stl b/sim/resources/zeroth/meshes/Rotor_2.stl
new file mode 100644
index 00000000..38311bce
Binary files /dev/null and b/sim/resources/zeroth/meshes/Rotor_2.stl differ
diff --git a/sim/resources/zeroth/meshes/foot_bracket_for_5dof_leg_v9.stl b/sim/resources/zeroth/meshes/foot_bracket_for_5dof_leg_v9.stl
new file mode 100644
index 00000000..2442217c
Binary files /dev/null and b/sim/resources/zeroth/meshes/foot_bracket_for_5dof_leg_v9.stl differ
diff --git a/sim/resources/zeroth/meshes/foot_bracket_for_5dof_leg_v9_2.stl b/sim/resources/zeroth/meshes/foot_bracket_for_5dof_leg_v9_2.stl
new file mode 100644
index 00000000..24398a89
Binary files /dev/null and b/sim/resources/zeroth/meshes/foot_bracket_for_5dof_leg_v9_2.stl differ
diff --git a/sim/resources/zeroth/meshes/leg_top_bracket_v8_1.stl b/sim/resources/zeroth/meshes/leg_top_bracket_v8_1.stl
new file mode 100644
index 00000000..d66f354b
Binary files /dev/null and b/sim/resources/zeroth/meshes/leg_top_bracket_v8_1.stl differ
diff --git a/sim/resources/zeroth/meshes/leg_top_bracket_v8_1_2.stl b/sim/resources/zeroth/meshes/leg_top_bracket_v8_1_2.stl
new file mode 100644
index 00000000..d2e329a9
Binary files /dev/null and b/sim/resources/zeroth/meshes/leg_top_bracket_v8_1_2.stl differ
diff --git a/sim/resources/zeroth/meshes/leg_top_bracket_v9.stl b/sim/resources/zeroth/meshes/leg_top_bracket_v9.stl
new file mode 100644
index 00000000..21df522f
Binary files /dev/null and b/sim/resources/zeroth/meshes/leg_top_bracket_v9.stl differ
diff --git a/sim/resources/zeroth/meshes/leg_top_bracket_v9_2.stl b/sim/resources/zeroth/meshes/leg_top_bracket_v9_2.stl
new file mode 100644
index 00000000..ebbf4949
Binary files /dev/null and b/sim/resources/zeroth/meshes/leg_top_bracket_v9_2.stl differ
diff --git a/sim/resources/zeroth/robot.urdf b/sim/resources/zeroth/robot.urdf
new file mode 100644
index 00000000..97103172
--- /dev/null
+++ b/sim/resources/zeroth/robot.urdf
@@ -0,0 +1,326 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/sim/resources/zeroth/robot_fixed.urdf b/sim/resources/zeroth/robot_fixed.urdf
new file mode 100644
index 00000000..d5dc68e7
--- /dev/null
+++ b/sim/resources/zeroth/robot_fixed.urdf
@@ -0,0 +1,326 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file