diff --git a/.gitignore b/.gitignore
index b71fa871..b642476e 100755
--- a/.gitignore
+++ b/.gitignore
@@ -27,4 +27,3 @@ out*/
# Training artifacts
wandb/
runs/
-stompy/
diff --git a/sim/env.py b/sim/env.py
index b512d58d..7877c5d7 100755
--- a/sim/env.py
+++ b/sim/env.py
@@ -16,7 +16,7 @@ def stompy_urdf_path(legs_only: bool = False) -> Path:
if legs_only:
stompy_path = model_dir() / "robot_fixed.urdf"
else:
- stompy_path = model_dir() / "robot.urdf"
+ stompy_path = model_dir() / "robot_fixed.urdf"
if not stompy_path.exists():
raise FileNotFoundError(f"URDF file not found: {stompy_path}")
@@ -28,7 +28,7 @@ def stompy_mjcf_path(legs_only: bool = False) -> Path:
if legs_only:
stompy_path = model_dir() / "robot_fixed.xml"
else:
- stompy_path = model_dir() / "robot.xml"
+ stompy_path = model_dir() / "robot_fixed.xml"
if not stompy_path.exists():
raise FileNotFoundError(f"MJCF file not found: {stompy_path}")
diff --git a/sim/humanoid_gym/envs/__init__.py b/sim/humanoid_gym/envs/__init__.py
index fc675d62..bdf67ac6 100755
--- a/sim/humanoid_gym/envs/__init__.py
+++ b/sim/humanoid_gym/envs/__init__.py
@@ -11,14 +11,10 @@
import isaacgym # isort:skip
import torch #isort:skip
# fmt: on
-from .getup_config import GetupCfg, GetupCfgPPO
-from .getup_env import GetupFreeEnv
-from .hexmove_config import HexmoveCfg, HexmoveCfgPPO
-from .hexmove_env import HexmoveFreeEnv
-from .legs_config import LegsCfg, LegsCfgPPO
-from .legs_env import LegsFreeEnv
-from .only_legs_config import OnlyLegsCfg, OnlyLegsCfgPPO
-from .only_legs_env import OnlyLegsFreeEnv
+# from .getup_config import GetupCfg, GetupCfgPPO
+# from .getup_env import GetupFreeEnv
+# from .only_legs_config import OnlyLegsCfg, OnlyLegsCfgPPO
+# from .only_legs_env import OnlyLegsFreeEnv
from .stompy_config import StompyCfg, StompyCfgPPO
from .stompy_env import StompyFreeEnv
@@ -32,9 +28,8 @@ def register_tasks() -> None:
from humanoid.utils.task_registry import task_registry
task_registry.register("stompy_ppo", StompyFreeEnv, StompyCfg(), StompyCfgPPO())
- task_registry.register("getup_ppo", GetupFreeEnv, GetupCfg(), GetupCfgPPO())
- task_registry.register("legs_ppo", LegsFreeEnv, LegsCfg(), LegsCfgPPO())
- task_registry.register("only_legs_ppo", OnlyLegsFreeEnv, OnlyLegsCfg(), OnlyLegsCfgPPO())
+ # task_registry.register("getup_ppo", GetupFreeEnv, GetupCfg(), GetupCfgPPO())
+ # task_registry.register("only_legs_ppo", OnlyLegsFreeEnv, OnlyLegsCfg(), OnlyLegsCfgPPO())
register_tasks()
diff --git a/sim/humanoid_gym/envs/stompy_config.py b/sim/humanoid_gym/envs/stompy_config.py
index 01164782..6c84b735 100755
--- a/sim/humanoid_gym/envs/stompy_config.py
+++ b/sim/humanoid_gym/envs/stompy_config.py
@@ -34,7 +34,7 @@ class safety:
# safety factors
pos_limit = 1.0
vel_limit = 1.0
- torque_limit = 1.0
+ torque_limit = 0.85
class asset(LeggedRobotCfg.asset):
file = str(stompy_urdf_path())
@@ -49,7 +49,7 @@ class asset(LeggedRobotCfg.asset):
terminate_after_contacts_on = ["link_upper_limb_assembly_7_dof_1_torso_1_top_skeleton_2"]
penalize_contacts_on = []
- self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
+ self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
flip_visual_attachments = False
replace_cylinder_with_capsule = False
fix_base_link = False
@@ -84,8 +84,8 @@ class noise_scales:
height_measurements = 0.1
class init_state(LeggedRobotCfg.init_state):
- pos = [0.0, 0.0, 1.15]
-
+ pos = [0.0, 0.0, 1.1]
+ rot = [0.0, 0.0, 0.7071068, 0.7071068]
default_joint_angles = {k: 0.0 for k in Stompy.all_joints()}
default_positions = Stompy.default_standing()
@@ -94,26 +94,8 @@ class init_state(LeggedRobotCfg.init_state):
class control(LeggedRobotCfg.control):
# PD Drive parameters:
- stiffness = {
- "shoulder": 200,
- "elbow": 200,
- "wrist": 200,
- "hand": 200,
- "torso": 200,
- "hip": 200,
- "ankle": 200,
- "knee": 200,
- }
- damping = {
- "shoulder": 10,
- "elbow": 10,
- "wrist": 10,
- "hand": 10,
- "torso": 10,
- "hip": 10,
- "ankle": 10,
- "knee": 10,
- }
+ stiffness = Stompy.stiffness()
+ damping = Stompy.damping()
# action scale: target angle = actionScale * action + defaultAngle
action_scale = 0.25
# decimation: Number of control action updates @ sim DT per policy DT
@@ -126,11 +108,11 @@ class sim(LeggedRobotCfg.sim):
class physx(LeggedRobotCfg.sim.physx):
num_threads = 12
- solver_type = 1 # 0: pgs, 1: tgs
+ solver_type = 0 # 0: pgs, 1: tgs
num_position_iterations = 4
- num_velocity_iterations = 0
+ num_velocity_iterations = 1
contact_offset = 0.01 # [m]
- rest_offset = -0.02 # [m]
+ rest_offset = 0.0 # [m]
bounce_threshold_velocity = 0.1 # [m/s]
max_depenetration_velocity = 1.0
max_gpu_contact_pairs = 2**23 # 2**24 -> needed for 8000 envs and more
@@ -144,7 +126,7 @@ class domain_rand:
randomize_base_mass = True
added_mass_range = [-1.0, 1.0]
- push_robots = True
+ push_robots = False
push_interval_s = 4
max_push_vel_xy = 0.2
max_push_ang_vel = 0.4
@@ -178,23 +160,23 @@ class rewards:
max_contact_force = 400 # forces above this value are penalized
class scales:
- # # reference motion tracking
- # joint_pos = 1.6
- # feet_clearance = 1.0
- # feet_contact_number = 1.2
- # # gait
- # feet_air_time = 1.0
- # 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.2
- # track_vel_hard = 0.5
+ # reference motion tracking
+ joint_pos = 1.6
+ feet_clearance = 1.0
+ feet_contact_number = 1.2
+ # gait
+ feet_air_time = 1.0
+ 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.2
+ track_vel_hard = 0.5
# above this was removed
# base pos
@@ -252,7 +234,7 @@ class runner:
# logging
save_interval = 100 # check for potential saves every this many iterations
- experiment_name = "Legs"
+ experiment_name = "Full"
run_name = ""
# load and resume
resume = False
diff --git a/sim/scripts/create_mjcf.py b/sim/scripts/create_mjcf.py
old mode 100644
new mode 100755
index 26c15dd9..45614cab
--- a/sim/scripts/create_mjcf.py
+++ b/sim/scripts/create_mjcf.py
@@ -49,7 +49,7 @@ def _pretty_print_xml(xml_string: str) -> str:
class Sim2SimRobot(mjcf.Robot):
"""A class to adapt the world in a Mujoco XML file."""
- def adapt_world(self, add_floor: bool = True, remove_frc_range: bool = False) -> None:
+ def adapt_world(self, add_floor: bool = True, remove_frc_range: bool = True) -> None:
root: ET.Element = self.tree.getroot()
if add_floor:
@@ -239,12 +239,12 @@ def adapt_world(self, add_floor: bool = True, remove_frc_range: bool = False) ->
index = list(body).index(geom)
body.insert(index + 1, new_geom)
- if remove_frc_range:
- for body in root.findall(".//body"):
- joints = list(body.findall("joint"))
- for join in joints:
- if "actuatorfrcrange" in join.attrib:
- join.attrib.pop("actuatorfrcrange")
+ for body in root.findall(".//body"):
+ joints = list(body.findall("joint"))
+ for join in joints:
+ print(join)
+ if "actuatorfrcrange" in join.attrib:
+ join.attrib.pop("actuatorfrcrange")
# Adding keyframe
default_standing = stompy.default_standing()
diff --git a/sim/stompy/joints.py b/sim/stompy/joints.py
index 6756f89e..628f5fb4 100755
--- a/sim/stompy/joints.py
+++ b/sim/stompy/joints.py
@@ -52,6 +52,38 @@ def __str__(self) -> str:
return f"[{self.__class__.__name__}]{parts_str}"
+class Torso(Node):
+ roll = "torso roll"
+
+
+class LeftHand(Node):
+ wrist_roll = "left wrist roll"
+ wrist_pitch = "left wrist pitch"
+ wrist_yaw = "left wrist yaw"
+
+
+class LeftArm(Node):
+ shoulder_yaw = "left shoulder yaw"
+ shoulder_pitch = "left shoulder pitch"
+ shoulder_roll = "left shoulder roll"
+ elbow_pitch = "left elbow pitch"
+ hand = LeftHand()
+
+
+class RightHand(Node):
+ wrist_roll = "right wrist roll"
+ wrist_pitch = "right wrist pitch"
+ wrist_yaw = "right wrist yaw"
+
+
+class RightArm(Node):
+ shoulder_yaw = "right shoulder yaw"
+ shoulder_pitch = "right shoulder pitch"
+ shoulder_roll = "right shoulder roll"
+ elbow_pitch = "right elbow pitch"
+ hand = RightHand()
+
+
class LeftLeg(Node):
hip_roll = "left hip roll"
hip_yaw = "left hip yaw"
@@ -76,80 +108,160 @@ class Legs(Node):
class Stompy(Node):
+ torso = Torso()
+ left_arm = LeftArm()
+ right_arm = RightArm()
legs = Legs()
- @classmethod
- def default_positions(cls) -> Dict[str, float]:
- return {}
-
@classmethod
def default_standing(cls) -> Dict[str, float]:
return {
+ Stompy.torso.roll: -0.502,
+ # arms
+ Stompy.left_arm.shoulder_pitch: -0.251,
+ Stompy.left_arm.shoulder_yaw: 1.82,
+ Stompy.left_arm.shoulder_roll: -1.44,
+ Stompy.right_arm.shoulder_pitch: 2.7,
+ Stompy.right_arm.shoulder_yaw: -1.82,
+ Stompy.right_arm.shoulder_roll: -2.57,
+ Stompy.left_arm.elbow_pitch: 2.07,
+ Stompy.right_arm.elbow_pitch: -2.57,
+ # hands
+ Stompy.left_arm.hand.wrist_roll: -2.51,
+ Stompy.left_arm.hand.wrist_pitch: 3.33,
+ Stompy.left_arm.hand.wrist_yaw: 0.0628,
+ Stompy.right_arm.hand.wrist_roll: 0,
+ Stompy.right_arm.hand.wrist_pitch: 0.251,
+ Stompy.right_arm.hand.wrist_yaw: 1.38,
# legs
- Stompy.legs.left.hip_pitch: 1.61,
- Stompy.legs.left.hip_yaw: 1,
- Stompy.legs.left.hip_roll: 0,
- Stompy.legs.left.knee_pitch: 2.05,
- Stompy.legs.left.ankle_pitch: 0.33,
- Stompy.legs.left.ankle_roll: 1.73,
- Stompy.legs.right.hip_pitch: 0,
- Stompy.legs.right.hip_yaw: -2.15,
- Stompy.legs.right.hip_roll: -1.6,
- Stompy.legs.right.knee_pitch: 2.16,
- Stompy.legs.right.ankle_pitch: 0.5,
- Stompy.legs.right.ankle_roll: 1.72,
+ Stompy.legs.left.hip_pitch: 0.502,
+ Stompy.legs.left.hip_roll: -1.57,
+ Stompy.legs.left.hip_yaw: -2.07,
+ Stompy.legs.left.knee_pitch: 3.39,
+ Stompy.legs.left.ankle_pitch: 1,
+ Stompy.legs.left.ankle_roll: 1.76,
+ Stompy.legs.right.hip_pitch: 1.13,
+ Stompy.legs.right.hip_roll: 0,
+ Stompy.legs.right.hip_yaw: 1.07,
+ Stompy.legs.right.knee_pitch: 0.879,
+ Stompy.legs.right.ankle_pitch: -0.502,
+ Stompy.legs.right.ankle_roll: 1.76,
}
@classmethod
def default_limits(cls) -> Dict[str, Dict[str, float]]:
return {
- Stompy.legs.left.hip_pitch: {
- "lower": 0.5,
- "upper": 2.69,
+ # torso
+ Stompy.torso.roll: {
+ "lower": -0.502,
+ "upper": -0.501,
},
- Stompy.legs.left.hip_yaw: {
- "lower": 0.5,
- "upper": 1.19,
+ # left arm
+ Stompy.left_arm.shoulder_pitch: {
+ "lower": -0.251,
+ "upper": -0.250,
+ },
+ Stompy.left_arm.shoulder_yaw: {
+ "lower": 1.82,
+ "upper": 1.821,
+ },
+ Stompy.left_arm.shoulder_roll: {
+ "lower": -1.44,
+ "upper": -1.439,
+ },
+ Stompy.left_arm.elbow_pitch: {
+ "lower": 2.07,
+ "upper": 2.071,
+ },
+ Stompy.left_arm.hand.wrist_roll: {
+ "lower": -2.51,
+ "upper": -2.509,
+ },
+ Stompy.left_arm.hand.wrist_pitch: {
+ "lower": 3.33,
+ "upper": 3.331,
+ },
+ Stompy.left_arm.hand.wrist_yaw: {
+ "lower": 0.0628,
+ "upper": 0.0638,
+ },
+ # right arm
+ Stompy.right_arm.shoulder_pitch: {
+ "lower": 2.7,
+ "upper": 2.701,
+ },
+ Stompy.right_arm.shoulder_yaw: {
+ "lower": -1.82,
+ "upper": -1.819,
+ },
+ Stompy.right_arm.shoulder_roll: {
+ "lower": -2.57,
+ "upper": -2.569,
+ },
+ Stompy.right_arm.elbow_pitch: {
+ "lower": -2.57,
+ "upper": -2.569,
+ },
+ Stompy.right_arm.hand.wrist_roll: {
+ "lower": 0,
+ "upper": 0.001,
+ },
+ Stompy.right_arm.hand.wrist_pitch: {
+ "lower": 0.251,
+ "upper": 0.252,
+ },
+ Stompy.right_arm.hand.wrist_yaw: {
+ "lower": 1.38,
+ "upper": 1.381,
+ },
+ # left leg
+ Stompy.legs.left.hip_pitch: {
+ "lower": -0.498,
+ "upper": 1.502,
},
Stompy.legs.left.hip_roll: {
- "lower": -0.5,
- "upper": 0.5,
+ "lower": -2.57,
+ "upper": -0.57,
+ },
+ Stompy.legs.left.hip_yaw: {
+ "lower": -3.07,
+ "upper": -1.07,
},
Stompy.legs.left.knee_pitch: {
- "lower": 0.5,
- "upper": 2.5,
+ "lower": 2.39,
+ "upper": 4.39,
},
Stompy.legs.left.ankle_pitch: {
- "lower": -0.8,
- "upper": 0.6,
+ "lower": 0,
+ "upper": 2,
},
Stompy.legs.left.ankle_roll: {
- "lower": 1,
- "upper": 2.3,
+ "lower": 0.76,
+ "upper": 2.76,
},
Stompy.legs.right.hip_pitch: {
+ "lower": 0.13,
+ "upper": 2.13,
+ },
+ Stompy.legs.right.hip_roll: {
"lower": -1,
"upper": 1,
},
Stompy.legs.right.hip_yaw: {
- "lower": -2.2,
- "upper": -1,
- },
- Stompy.legs.right.hip_roll: {
- "lower": -2.39,
- "upper": -1,
+ "lower": 0.07,
+ "upper": 2.07,
},
Stompy.legs.right.knee_pitch: {
- "lower": 1.54,
- "upper": 3,
+ "lower": -0.121,
+ "upper": 1.879,
},
Stompy.legs.right.ankle_pitch: {
- "lower": 0,
- "upper": 1.5,
+ "lower": -1.502,
+ "upper": 0.498,
},
Stompy.legs.right.ankle_roll: {
- "lower": 1,
- "upper": 2.3,
+ "lower": 0.76,
+ "upper": 2.76,
},
}
@@ -163,6 +275,14 @@ def stiffness(cls) -> Dict[str, float]:
"knee pitch": 150,
"ankle pitch": 45,
"ankle roll": 45,
+ "shoulder pitch": 0,
+ "shoulder yaw": 0,
+ "shoulder roll": 0,
+ "elbow pitch": 0,
+ "wrist roll": 0,
+ "wrist pitch": 0,
+ "wrist yaw": 0,
+ "torso roll": 0,
}
# d_gains
@@ -173,8 +293,16 @@ def damping(cls) -> Dict[str, float]:
"hip yaw": 10,
"hip roll": 10,
"knee pitch": 10,
- "ankle pitch": 3,
- "ankle roll": 3,
+ "ankle pitch": 10,
+ "ankle roll": 10,
+ "shoulder pitch": 0,
+ "shoulder yaw": 0,
+ "shoulder roll": 0,
+ "elbow pitch": 0,
+ "wrist roll": 0,
+ "wrist pitch": 0,
+ "wrist yaw": 0,
+ "torso roll": 0,
}
# pos_limits
@@ -187,18 +315,34 @@ def effort(cls) -> Dict[str, float]:
"knee pitch": 90,
"ankle pitch": 24,
"ankle roll": 24,
+ "shoulder pitch": 0,
+ "shoulder yaw": 0,
+ "shoulder roll": 0,
+ "elbow pitch": 0,
+ "wrist roll": 0,
+ "wrist pitch": 0,
+ "wrist yaw": 0,
+ "torso roll": 0,
}
# vel_limits
@classmethod
def velocity(cls) -> Dict[str, float]:
return {
- "hip pitch": 25,
+ "hip pitch": 40,
"hip yaw": 40,
"hip roll": 40,
"knee pitch": 40,
- "ankle pitch": 40,
- "ankle roll": 40,
+ "ankle pitch": 12,
+ "ankle roll": 12,
+ "shoulder pitch": 0,
+ "shoulder yaw": 0,
+ "shoulder roll": 0,
+ "elbow pitch": 0,
+ "wrist roll": 0,
+ "wrist pitch": 0,
+ "wrist yaw": 0,
+ "torso roll": 0,
}
@classmethod
diff --git a/sim/stompy/robot_fixed.urdf b/sim/stompy/robot_fixed.urdf
new file mode 100755
index 00000000..4b99cdf6
--- /dev/null
+++ b/sim/stompy/robot_fixed.urdf
@@ -0,0 +1,3818 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/sim/stompy/robot_fixed.xml b/sim/stompy/robot_fixed.xml
new file mode 100755
index 00000000..ec9ea188
--- /dev/null
+++ b/sim/stompy/robot_fixed.xml
@@ -0,0 +1,697 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+