|
| 1 | +"""Defines a more Pythonic interface for specifying the joint names. |
| 2 | +
|
| 3 | +The best way to re-generate this snippet for a new robot is to use the |
| 4 | +`sim/scripts/print_joints.py` script. This script will print out a hierarchical |
| 5 | +tree of the various joint names in the robot. |
| 6 | +""" |
| 7 | + |
| 8 | +import textwrap |
| 9 | +from abc import ABC |
| 10 | +from typing import Dict, List, Tuple, Union |
| 11 | + |
| 12 | + |
| 13 | +class Node(ABC): |
| 14 | + @classmethod |
| 15 | + def children(cls) -> List["Union[Node, str]"]: |
| 16 | + return [ |
| 17 | + attr |
| 18 | + for attr in (getattr(cls, attr) for attr in dir(cls) if not attr.startswith("__")) |
| 19 | + if isinstance(attr, (Node, str)) |
| 20 | + ] |
| 21 | + |
| 22 | + @classmethod |
| 23 | + def joints(cls) -> List[str]: |
| 24 | + return [ |
| 25 | + attr |
| 26 | + for attr in (getattr(cls, attr) for attr in dir(cls) if not attr.startswith("__")) |
| 27 | + if isinstance(attr, str) |
| 28 | + ] |
| 29 | + |
| 30 | + @classmethod |
| 31 | + def joints_motors(cls) -> List[Tuple[str, str]]: |
| 32 | + joint_names: List[Tuple[str, str]] = [] |
| 33 | + for attr in dir(cls): |
| 34 | + if not attr.startswith("__"): |
| 35 | + attr2 = getattr(cls, attr) |
| 36 | + if isinstance(attr2, str): |
| 37 | + joint_names.append((attr, attr2)) |
| 38 | + |
| 39 | + return joint_names |
| 40 | + |
| 41 | + @classmethod |
| 42 | + def all_joints(cls) -> List[str]: |
| 43 | + leaves = cls.joints() |
| 44 | + for child in cls.children(): |
| 45 | + if isinstance(child, Node): |
| 46 | + leaves.extend(child.all_joints()) |
| 47 | + return leaves |
| 48 | + |
| 49 | + def __str__(self) -> str: |
| 50 | + parts = [str(child) for child in self.children()] |
| 51 | + parts_str = textwrap.indent("\n" + "\n".join(parts), " ") |
| 52 | + return f"[{self.__class__.__name__}]{parts_str}" |
| 53 | + |
| 54 | + |
| 55 | +class Torso(Node): |
| 56 | + roll = "torso_joint" |
| 57 | + |
| 58 | + |
| 59 | +class LeftArm(Node): |
| 60 | + shoulder_yaw = "left_shoulder_yaw_joint" |
| 61 | + shoulder_pitch = "left_shoulder_pitch_joint" |
| 62 | + shoulder_roll = "left_shoulder_roll_joint" |
| 63 | + elbow_pitch = "left_elbow_pitch_joint" |
| 64 | + |
| 65 | + |
| 66 | +class RightArm(Node): |
| 67 | + shoulder_yaw = "right_shoulder_yaw_joint" |
| 68 | + shoulder_pitch = "right_shoulder_pitch_joint" |
| 69 | + shoulder_roll = "right_shoulder_roll_joint" |
| 70 | + elbow_pitch = "right_elbow_pitch_joint" |
| 71 | + |
| 72 | + |
| 73 | +class LeftLeg(Node): |
| 74 | + hip_roll = "left_hip_roll_joint" |
| 75 | + hip_yaw = "left_hip_yaw_joint" |
| 76 | + hip_pitch = "left_hip_pitch_joint" |
| 77 | + knee_pitch = "left_knee_joint" |
| 78 | + ankle_pitch = "left_ankle_pitch_joint" |
| 79 | + ankle_roll = "left_ankle_roll_joint" |
| 80 | + |
| 81 | + |
| 82 | +class RightLeg(Node): |
| 83 | + hip_roll = "right_hip_roll_joint" |
| 84 | + hip_yaw = "right_hip_yaw_joint" |
| 85 | + hip_pitch = "right_hip_pitch_joint" |
| 86 | + knee_pitch = "right_knee_joint" |
| 87 | + ankle_pitch = "right_ankle_pitch_joint" |
| 88 | + ankle_roll = "right_ankle_roll_joint" |
| 89 | + |
| 90 | + |
| 91 | +class Legs(Node): |
| 92 | + left = LeftLeg() |
| 93 | + right = RightLeg() |
| 94 | + |
| 95 | + |
| 96 | +class Stompy(Node): |
| 97 | + torso = Torso() |
| 98 | + left_arm = LeftArm() |
| 99 | + right_arm = RightArm() |
| 100 | + legs = Legs() |
| 101 | + |
| 102 | + @classmethod |
| 103 | + def default_standing(cls) -> Dict[str, float]: |
| 104 | + return { # = target angles [rad] when action = 0.0 |
| 105 | + # left leg |
| 106 | + Stompy.legs.left.hip_yaw: 0, |
| 107 | + Stompy.legs.left.hip_roll: 0, |
| 108 | + Stompy.legs.left.hip_pitch: -0.6, |
| 109 | + Stompy.legs.left.knee_pitch: 1.2, |
| 110 | + Stompy.legs.left.ankle_pitch: -0.6, |
| 111 | + Stompy.legs.left.ankle_roll: 0.0, |
| 112 | + # right leg |
| 113 | + Stompy.legs.right.hip_yaw: 0, |
| 114 | + Stompy.legs.right.hip_roll: 0, |
| 115 | + Stompy.legs.right.hip_pitch: -0.6, |
| 116 | + Stompy.legs.right.knee_pitch: 1.2, |
| 117 | + Stompy.legs.right.ankle_pitch: -0.6, |
| 118 | + Stompy.legs.right.ankle_roll: 0.0, |
| 119 | + # torso |
| 120 | + Stompy.torso.roll: 0, |
| 121 | + # left arm |
| 122 | + Stompy.left_arm.shoulder_pitch: 0.4, |
| 123 | + Stompy.left_arm.shoulder_roll: 0, |
| 124 | + Stompy.left_arm.shoulder_yaw: 0, |
| 125 | + Stompy.left_arm.elbow_pitch: 0.3, |
| 126 | + # right arm |
| 127 | + Stompy.right_arm.shoulder_pitch: 0.4, |
| 128 | + Stompy.right_arm.shoulder_roll: 0, |
| 129 | + Stompy.right_arm.shoulder_yaw: 0, |
| 130 | + Stompy.right_arm.elbow_pitch: 0.3, |
| 131 | + } |
| 132 | + |
| 133 | + # p_gains |
| 134 | + @classmethod |
| 135 | + def stiffness(cls) -> Dict[str, float]: |
| 136 | + return { |
| 137 | + "hip_pitch": 200, |
| 138 | + "hip_yaw": 200, |
| 139 | + "hip_roll": 200, |
| 140 | + "knee_joint": 300, |
| 141 | + "ankle_pitch": 40, |
| 142 | + "ankle_roll": 40, |
| 143 | + "shoulder_pitch": 80, |
| 144 | + "shoulder_yaw": 40, |
| 145 | + "shoulder_roll": 80, |
| 146 | + "elbow_pitch": 60, |
| 147 | + "torso_joint": 600, |
| 148 | + } |
| 149 | + |
| 150 | + # d_gains |
| 151 | + @classmethod |
| 152 | + def damping(cls) -> Dict[str, float]: |
| 153 | + return { |
| 154 | + "hip_pitch": 5, |
| 155 | + "hip_yaw": 5, |
| 156 | + "hip_roll": 5, |
| 157 | + "knee_joint": 7.5, |
| 158 | + "ankle_pitch": 1, |
| 159 | + "ankle_roll": 0.3, |
| 160 | + "shoulder_pitch": 2, |
| 161 | + "shoulder_yaw": 1, |
| 162 | + "shoulder_roll": 2, |
| 163 | + "elbow_pitch": 1, |
| 164 | + "torso_joint": 15, |
| 165 | + } |
| 166 | + |
| 167 | + |
| 168 | +def print_joints() -> None: |
| 169 | + joints = Stompy.all_joints() |
| 170 | + assert len(joints) == len(set(joints)), "Duplicate joint names found!" |
| 171 | + print(Stompy()) |
| 172 | + |
| 173 | + |
| 174 | +if __name__ == "__main__": |
| 175 | + # python -m sim.stompy.joints |
| 176 | + print_joints() |
0 commit comments