diff --git a/playground/common/contact_aided_invariant_ekf/__init__.py b/playground/common/contact_aided_invariant_ekf/__init__.py
new file mode 100644
index 0000000..21d6347
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/__init__.py
@@ -0,0 +1,6 @@
+"""
+Contact aided invariant extended Kalman Filter
+Author: Nathan Kong
+Description: Contact aided invariant extended Kalman Filter TODO: fill in description.
+ Following invariant-ekf implementation from https://github.com/RossHartley/invariant-ekf
+"""
diff --git a/playground/common/contact_aided_invariant_ekf/contact_aided_invariant_ekf.py b/playground/common/contact_aided_invariant_ekf/contact_aided_invariant_ekf.py
new file mode 100644
index 0000000..90c1e25
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/contact_aided_invariant_ekf.py
@@ -0,0 +1,437 @@
+import numpy as np
+from playground.common.contact_aided_invariant_ekf.observation import Observation, check_measurement_is_empty
+from typing import Optional
+from playground.common.contact_aided_invariant_ekf.robot_state import RobotState
+from playground.common.contact_aided_invariant_ekf.lie_group import exp_so3, exp_sek3, adjoint_sek3, skew
+from playground.common.contact_aided_invariant_ekf.noise_params import NoiseParams
+from playground.common.contact_aided_invariant_ekf.utils import remove_row_and_column, GRAVITY_ACCELERATION
+from playground.common.contact_aided_invariant_ekf.robot_kinematics import Kinematics
+
+
+class Landmark:
+ def __init__(self, id_in: int, position_in: np.ndarray):
+ """
+ Represents a landmark with an ID and a 3D position.
+
+ Args:
+ id_in (int): The landmark ID.
+ position_in (np.ndarray): A 3D numpy array representing the landmark position.
+ """
+ self.id = id_in
+ self.position = np.array(position_in, dtype=float) # Ensure it's a NumPy array
+
+ def __repr__(self):
+ return f"Landmark(id={self.id}, position={self.position})"
+
+
+class RightInEKF:
+ def __init__(self, state: Optional[RobotState] = None, noise_params: Optional[NoiseParams] = None):
+ self.g_ = np.array([0, 0, GRAVITY_ACCELERATION])
+
+ if state is None:
+ state = RobotState()
+ self.state_ = state
+
+ if noise_params is None:
+ noise_params = NoiseParams()
+ self.noise_params_ = noise_params
+
+ self.prior_landmarks_ = {}
+ self.estimated_landmarks_ = {}
+ self.estimated_contact_positions_ = {}
+ self.contacts_ = {}
+
+ def get_state(self):
+ return self.state_
+
+ def set_state(self, state):
+ self.state_ = state
+
+ def get_noise_params(self):
+ return self.noise_params_
+
+ def set_noise_params(self, params):
+ self.noise_params_ = params
+
+ def get_prior_landmarks(self):
+ return self.prior_landmarks_
+
+ def set_prior_landmarks(self, prior_landmarks):
+ self.prior_landmarks_ = prior_landmarks
+
+ def get_estimated_landmarks(self):
+ return self.estimated_landmarks_
+
+ def get_estimated_contact_positions(self):
+ return self.estimated_contact_positions_
+
+ def set_contacts(self, contacts: tuple[int, bool]):
+ for contact_tuple in contacts:
+ contact_id, is_contact = contact_tuple
+ self.contacts_[contact_id] = is_contact
+
+ def get_contacts(self):
+ return self.contacts_
+
+
+ def propagate(self, m: np.ndarray, dt: float):
+ """
+ A priori Invariant EKF update. Note: bias does not evolve so it is not captured in the state, however, is considered in the covariance matrix.
+ """
+ w = m[:3] - self.state_.get_gyroscope_bias().squeeze() # Angular Velocity
+ a = m[3:] - self.state_.get_accelerometer_bias().squeeze() # Linear Acceleration
+
+ X = self.state_.get_x()
+ P = self.state_.get_p()
+
+ # Extract State
+ R = self.state_.get_rotation()
+ v = self.state_.get_velocity()
+ p = self.state_.get_position()
+
+ # Strapdown IMU motion model
+ phi = w * dt
+ R_pred = R @ exp_so3(phi)
+ v_pred = v + (R @ a + self.g_) * dt
+ p_pred = p + v * dt + 0.5 * (R @ a + self.g_) * dt**2
+
+ # Set new state (bias has constant dynamics)
+ self.state_.set_rotation(R_pred)
+ self.state_.set_velocity(v_pred)
+ self.state_.set_position(p_pred)
+
+ # ---- Linearized invariant error dynamics -----
+ dimX = self.state_.dim_x()
+ dimP = self.state_.dim_p()
+ dimTheta = self.state_.dim_theta()
+
+ A = np.zeros((dimP, dimP))
+
+ # TODO: we don't need to compute inertia terms for A everytime.
+ A[3:6, 0:3] = skew(self.g_)
+ A[6:9, 3:6] = np.eye(3)
+
+ # Bias terms
+ A[0:3, dimP-dimTheta:dimP-dimTheta+3] = -R
+ A[3:6, dimP-dimTheta+3:dimP-dimTheta+6] = -R
+
+ # TODO: vectorize?
+ for i in range(3, dimX):
+ A[3*i-6:3*i-3, dimP-dimTheta:dimP-dimTheta+3] = -skew(X[0:3, i]) @ R
+ # Vectorized computation for the loop
+ # indices = np.arange(3, dimX)
+ # A[3*indices-6, dimP-dimTheta:dimP-dimTheta+3] = -skew(X[0:3, indices]) @ R
+
+ # Noise terms. TODO: vectorize
+ Qk = np.zeros((dimP, dimP))
+ Qk[0:3, 0:3] = self.noise_params_.get_gyroscope_cov()
+ Qk[3:6, 3:6] = self.noise_params_.get_accelerometer_cov()
+
+ for _, idx in self.estimated_contact_positions_.items():
+ Qk[3+3*(idx-3):3+3*(idx-3)+3, 3+3*(idx-3):3+3*(idx-3)+3] = self.noise_params_.get_contact_cov()
+
+ Qk[dimP-dimTheta:dimP-dimTheta+3, dimP-dimTheta:dimP-dimTheta+3] = self.noise_params_.get_gyroscope_bias_cov()
+ Qk[dimP-dimTheta+3:dimP-dimTheta+6, dimP-dimTheta+3:dimP-dimTheta+6] = self.noise_params_.get_accelerometer_bias_cov()
+
+ # Discretization
+ identity = np.eye(dimP)
+ Phi = identity + A * dt # Fast approximation of exp(A*dt)
+ Adj = identity.copy()
+ Adj[:dimP-dimTheta, :dimP-dimTheta] = adjoint_sek3(X)
+ PhiAdj = Phi @ Adj
+ Qk_hat = PhiAdj @ np.diag(np.diag(Qk)) @ PhiAdj.T * dt
+
+ # Propagate Covariance
+ P_pred = Phi @ P @ Phi.T + Qk_hat
+
+ # Set new covariance
+ self.state_.set_p(P_pred)
+
+ def correct(self, obs: Observation):
+ if obs.is_empty():
+ return
+ # print("Obs: ",obs)
+ P = self.state_.get_p()
+ PHT = P @ obs.H.T
+ S = obs.H @ PHT + obs.N
+ K = PHT @ np.linalg.inv(S)
+
+ BigX = self.state_.copy_diag_x(obs.Y.shape[0] // self.state_.dim_x())
+ Z = BigX @ obs.Y - obs.b
+ delta = K @ obs.PI @ Z
+
+ dX = exp_sek3(delta[:-self.state_.dim_theta()])
+ dTheta = delta[-self.state_.dim_theta():]
+
+ X_new = dX @ self.state_.get_x()
+ Theta_new = self.state_.get_theta().squeeze() + dTheta
+
+ self.state_.set_x(X_new)
+ self.state_.set_theta(Theta_new)
+
+ IKH = np.eye(self.state_.dim_p()) - K @ obs.H
+ P_new = IKH @ P @ IKH.T + K @ obs.N @ K.T
+ self.state_.set_p(P_new)
+
+ def correct_landmarks(self, measured_landmarks: list[Landmark], current_rotation: np.ndarray):
+ Y = np.array([])
+ b = np.array([])
+ H = np.zeros((0, self.state_.dim_p()))
+ N = np.zeros((0, 0))
+ PI = np.zeros((0, 0))
+
+ new_landmarks = []
+ used_landmark_ids = set()
+
+ for landmark in measured_landmarks:
+ if landmark.id in used_landmark_ids:
+ # print("Duplicate landmark ID detected! Skipping measurement.")
+ continue
+ used_landmark_ids.add(landmark.id)
+
+ if landmark.id in self.prior_landmarks_:
+ p_wl = self.prior_landmarks_[landmark.id]
+ dim_x = self.state_.dim_x()
+ dim_p = self.state_.dim_p()
+
+ Y = np.append(Y, np.zeros(dim_x))
+ Y[-dim_x+3:-dim_x+6] = landmark.position
+ Y[-dim_x+4] = 1
+
+ b = np.append(b, np.zeros(dim_x))
+ b[-dim_x+3:-dim_x+6] = p_wl
+ b[-dim_x+4] = 1
+
+ new_H = np.zeros((3, dim_p))
+ new_H[:, :3] = self.skew(p_wl)
+ new_H[:, 6:9] = -np.eye(3)
+ H = np.vstack((H, new_H))
+
+ new_N = np.zeros((N.shape[0] + 3, N.shape[1] + 3))
+ new_N[:N.shape[0], :N.shape[1]] = N
+ new_N[-3:, -3:] = current_rotation @ self.noise_params_.get_landmark_cov() @ current_rotation.T
+ N = new_N
+
+ new_PI = np.zeros((PI.shape[0] + 3, PI.shape[1] + dim_x))
+ new_PI[:PI.shape[0], :PI.shape[1]] = PI
+ new_PI[-3:, -dim_x:] = np.zeros((3, dim_x))
+ new_PI[-3:, -3:] = np.eye(3)
+ PI = new_PI
+
+ elif landmark.id in self.estimated_landmarks:
+ dim_x = self.state_.dim_x()
+ dim_p = self.state_.dim_p()
+ idx = self.estimated_landmarks[landmark.id]
+
+ Y = np.append(Y, np.zeros(dim_x))
+ Y[-dim_x+3:-dim_x+6] = landmark.position
+ Y[-dim_x+4] = 1
+ Y[-dim_x+idx] = -1
+
+ b = np.append(b, np.zeros(dim_x))
+ b[-dim_x+4] = 1
+ b[-dim_x+idx] = -1
+
+ new_H = np.zeros((3, dim_p))
+ new_H[:, 6:9] = -np.eye(3)
+ new_H[:, 3*idx-6:3*idx-3] = np.eye(3)
+ H = np.vstack((H, new_H))
+
+ new_N = np.zeros((N.shape[0] + 3, N.shape[1] + 3))
+ new_N[:N.shape[0], :N.shape[1]] = N
+ new_N[-3:, -3:] = current_rotation @ self.noise_params_.get_landmark_cov() @ current_rotation.T
+ N = new_N
+
+ new_PI = np.zeros((PI.shape[0] + 3, PI.shape[1] + dim_x))
+ new_PI[:PI.shape[0], :PI.shape[1]] = PI
+ new_PI[-3:, -dim_x:] = np.zeros((3, dim_x))
+ new_PI[-3:, -3:] = np.eye(3)
+ PI = new_PI
+
+ else:
+ new_landmarks.append(landmark)
+
+ obs = Observation(Y, b, H, N, PI)
+ if not obs.is_empty():
+ self.correct(obs)
+
+ if new_landmarks:
+ X_aug = self.state_.get_x()
+ P_aug = self.state_.get_p()
+ p = self.state_.get_position()
+
+ for landmark in new_landmarks:
+ start_idx = X_aug.shape[0]
+ X_aug = np.pad(X_aug, ((0, 1), (0, 1)), mode='constant')
+ X_aug[start_idx, start_idx] = 1
+ X_aug[:3, start_idx] = p + current_rotation @ landmark.position
+
+ F = np.zeros((self.state_.dim_p() + 3, self.state_.dim_p()))
+ F[:self.state_.dim_p() - self.state_.dim_theta(), :self.state_.dim_p() - self.state_.dim_theta()] = np.eye(self.state_.dim_p() - self.state_.dim_theta())
+ F[self.state_.dim_p() - self.state_.dim_theta():self.state_.dim_p() - self.state_.dim_theta() + 3, 6:9] = np.eye(3)
+ F[self.state_.dim_p() - self.state_.dim_theta() + 3:, self.state_.dim_p() - self.state_.dim_theta():] = np.eye(self.state_.dim_theta())
+
+ G = np.zeros((F.shape[0], 3))
+ G[-self.state_.dim_theta()-3:, :] = current_rotation
+ P_aug = (F @ P_aug @ F.T + G @ self.noise_params_.get_landmark_cov() @ G.T)
+
+ self.state_.set_x(X_aug)
+ self.state_.set_p(P_aug)
+ self.estimated_landmarks_[landmark.id] = start_idx
+
+ def correct_kinematics(self, measured_kinematics: list[Kinematics]):
+ remove_contacts = []
+ new_contacts: list[Kinematics] = []
+ used_contact_ids = set()
+ # TODO: find out if we want R to actually be held constant and not utilized for other updates.
+ R = self.state_.get_rotation()
+
+ for kinematic in measured_kinematics:
+ contact_id = kinematic.id
+
+ # Detect and skip if an ID is not unique
+ if contact_id in used_contact_ids:
+ # print("Duplicate contact ID detected! Skipping measurement.")
+ continue
+ else:
+ used_contact_ids.add(contact_id)
+
+ # Find contact indicator for the kinematics measurement
+ if contact_id not in self.contacts_:
+ continue # Skip if contact state is unknown
+ contact_indicated = self.contacts_[contact_id]
+
+ # Find the estimated contact position
+ found = contact_id in self.estimated_contact_positions_
+ # print(f"Contact indicated: {contact_indicated}, found: {found}")
+
+ # If contact is not indicated and id is found in estimated_contacts_, then remove state
+ if not contact_indicated and found:
+ remove_contacts.append((contact_id, self.estimated_contact_positions_[contact_id]))
+ # If contact is indicated and id is not found in estimated_contacts_, then augment state
+ elif contact_indicated and not found:
+ new_contacts.append(kinematic)
+ # If contact is indicated and id is found in estimated_contacts_, then correct using kinematics
+ elif contact_indicated and found:
+ obs = self._create_observation_from_kinematics(kinematics=kinematic, current_rotation=R)
+ if not obs.is_empty():
+ self.correct(obs)
+
+ # Remove contacts from state
+ self._remove_contacts_from_state(remove_contacts)
+
+ # Add contacts to state
+ self._add_contacts_to_state(new_contacts, current_rotation=R)
+
+ def _create_observation_from_kinematics(
+ self,
+ kinematics: Kinematics,
+ current_rotation: np.ndarray) -> Observation:
+ dim_x = self.state_.dim_x()
+ dim_p = self.state_.dim_p()
+
+ Y = np.zeros(dim_x)
+ b = np.zeros(dim_x)
+ H = np.zeros((3, dim_p))
+ N = np.zeros((3, 3))
+ PI = np.zeros((3, dim_x))
+
+ # If empty, we will just return an empty observation.
+ if check_measurement_is_empty(Y=Y):
+ return Observation(Y, b, H, N, PI)
+
+ # Modify Y
+ Y[0:3] = kinematics.pose[0:3, 3] # p_bc
+ Y[4] = 1
+ Y[self.estimated_contact_positions_[kinematics.id]] = -1
+
+ # Modify b
+ b[0:3] = np.zeros(3)
+ b[4] = 1
+ b[self.estimated_contact_positions_[kinematics.id]] = -1
+
+ # Modify H
+ H[0:3, 6:9] = -np.eye(3)
+ H[0:3, 3 * self.estimated_contact_positions_[kinematics.id] - 6:3 * self.estimated_contact_positions_[kinematics.id] - 3] = np.eye(3)
+
+ # Modify N
+ N[0:3, 0:3] = current_rotation @ kinematics.covariance[3:6, 3:6] @ current_rotation.T
+
+ # Modify PI
+ PI[0:3, 0:3] = np.eye(3)
+
+ # Create Observation object (if defined)
+ obs = Observation(Y, b, H, N, PI)
+ return obs
+
+ def _remove_contacts_from_state(self, remove_contacts: list[tuple]):
+ if remove_contacts:
+ X_rem = self.state_.get_x()
+ P_rem = self.state_.get_p()
+ for contact in sorted(remove_contacts, key=lambda x: x[1], reverse=True):
+ # Sort in descending order to avoid index shift issues
+ self.estimated_contact_positions_.pop(contact[0], None)
+
+ # Remove row and column from X
+ X_rem = remove_row_and_column(X_rem, contact[1])
+
+ # Remove 3 rows and columns from P
+ start_index = 3 + 3 * (contact[1] - 3)
+ for _ in range(3):
+ P_rem = remove_row_and_column(P_rem, start_index)
+
+ # Update indices in estimated landmarks and contact positions
+ self.estimated_landmarks_ = {
+ k: (v - 1 if v > contact[1] else v)
+ for k, v in self.estimated_landmarks_.items()
+ }
+ self.estimated_contact_positions_ = {
+ k: (v - 1 if v > contact[1] else v)
+ for k, v in self.estimated_contact_positions_.items()
+ }
+
+ # Update state
+ self.state_.set_x(X_rem)
+ self.state_.set_p(P_rem)
+
+ def _add_contacts_to_state(self, new_contacts: list[Kinematics], current_rotation: np.ndarray):
+ # Augment state with newly detected contacts
+ if new_contacts:
+ X_aug = self.state_.get_x()
+ P_aug = self.state_.get_p()
+ p = self.state_.get_position()
+ for contact in new_contacts:
+ # Initialize new landmark mean
+ start_index = X_aug.shape[0]
+
+ # Resize the matrix by adding an additional row and column
+ X_aug = np.pad(X_aug, ((0, 1), (0, 1)), mode='constant', constant_values=0)
+
+ # Set the new diagonal entry to 1
+ X_aug[start_index, start_index] = 1
+
+ # Update the new column with the transformed position
+ X_aug[:3, start_index] = p + current_rotation @ contact.pose[:3, 3]
+ # print("X_aug: ", X_aug)
+
+ # Initialize new landmark covariance
+ F = np.zeros((self.state_.dim_p() + 3, self.state_.dim_p()))
+
+ # Block assignment
+ F[:self.state_.dim_p() - self.state_.dim_theta(), :self.state_.dim_p() - self.state_.dim_theta()] = np.eye(self.state_.dim_p() - self.state_.dim_theta()) # for old X
+ F[self.state_.dim_p() - self.state_.dim_theta():self.state_.dim_p() - self.state_.dim_theta() + 3, 6:9] = np.eye(3) # for new landmark
+ F[self.state_.dim_p() - self.state_.dim_theta() + 3:, self.state_.dim_p() - self.state_.dim_theta():] = np.eye(self.state_.dim_theta()) # for theta
+ # print("F: ", F)
+
+ G = np.zeros((F.shape[0], 3))
+ G[-self.state_.dim_theta() - 3:-self.state_.dim_theta(), :] = current_rotation
+ # print("G: ", G)
+ P_aug = F @ P_aug @ F.T + G @ contact.covariance[3:6, 3:6] @ G.T
+
+ # print("P_aug: ", P_aug)
+ # Update state and covariance
+ self.state_.set_x(X_aug)
+ self.state_.set_p(P_aug)
+
+ # Add to list of estimated contact positions
+ self.estimated_contact_positions_[contact.id] = start_index
diff --git a/playground/common/contact_aided_invariant_ekf/drake_kinematics.py b/playground/common/contact_aided_invariant_ekf/drake_kinematics.py
new file mode 100644
index 0000000..22b270d
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/drake_kinematics.py
@@ -0,0 +1,122 @@
+import numpy as np
+from typing import Optional
+from playground.common.contact_aided_invariant_ekf.robot_kinematics import Kinematics
+
+from pydrake.all import (
+ MultibodyPlant,
+ Parser,
+ DiagramBuilder,
+ AddMultibodyPlantSceneGraph,
+ RigidTransform,
+ JacobianWrtVariable,
+ StartMeshcat,
+ MeshcatVisualizer
+)
+
+
+class DrakeKinematics:
+ def __init__(
+ self,
+ imu_frame_name: str,
+ end_effector_frame_name_to_id_map: dict[str],
+ urdf_model_path: str,
+ end_effector_offset_map: Optional[dict[str, list]] = None,
+ visualize: bool = True
+ ):
+ self.end_effector_frame_name_to_id_map = end_effector_frame_name_to_id_map
+
+ self.builder = DiagramBuilder()
+ plant_and_scene_graph = AddMultibodyPlantSceneGraph(self.builder, time_step=0.01)
+ self.plant: MultibodyPlant = plant_and_scene_graph[0]
+ self.scene_graph = plant_and_scene_graph[1]
+
+ parser = Parser(self.plant)
+ parser.AddModels(urdf_model_path)
+
+ self.visualize = visualize
+ if visualize:
+ meshcat = StartMeshcat()
+ MeshcatVisualizer.AddToBuilder(self.builder, self.scene_graph, meshcat)
+
+ self.imu_frame = self.plant.GetFrameByName(imu_frame_name)
+ self.plant.WeldFrames(
+ self.plant.world_frame(),
+ self.imu_frame,
+ RigidTransform()
+ )
+ self.plant.Finalize()
+ self.diagram = self.builder.Build()
+ self.context = self.diagram.CreateDefaultContext()
+
+ self.end_effector_body_map = {}
+ self.end_effector_frame_map = {}
+ for name in end_effector_frame_name_to_id_map:
+ self.end_effector_frame_map[name] = self.plant.GetFrameByName(name)
+ self.end_effector_body_map[name] = self.plant.GetBodyByName(name)
+
+ zero_offset = [0.0, 0.0, 0.0]
+ if end_effector_offset_map is None:
+ end_effector_offset_map = {name: zero_offset for name in end_effector_frame_name_to_id_map}
+ self.end_effector_offset_map = end_effector_offset_map
+
+ # Get the joint mapping
+ self.joint_name_to_idx_map = {}
+ for joint_idx in self.plant.GetJointIndices():
+ joint = self.plant.get_joint(joint_idx)
+ if joint.num_positions() == 1:
+ self.joint_name_to_idx_map[joint.name()] = joint.position_start()
+
+ def compute_fk(self, joint_positions: np.ndarray) -> dict[str, np.ndarray]:
+ """
+ Note: expect joint positions to be in the order of joing_name_to_idx_map
+ """
+ plant_context = self.plant.GetMyMutableContextFromRoot(self.context)
+ self.plant.SetPositions(plant_context, joint_positions)
+ if self.visualize:
+ self.diagram.ForcedPublish(self.context)
+
+ end_effector_pose_map = {}
+ for name, body in self.end_effector_body_map.items():
+ rigid_transform: RigidTransform = self.plant.EvalBodyPoseInWorld(
+ plant_context,
+ self.end_effector_body_map[name]
+ )
+ # Update the translation with the offset
+ offset_rigid_transform = rigid_transform @ RigidTransform(
+ self.end_effector_offset_map[name]
+ ) # Apply in the body frame of the EE.
+ end_effector_pose_map[name] = offset_rigid_transform.GetAsMatrix4()
+ return end_effector_pose_map
+
+ def compute_analytical_jacobians(self) -> dict[str, np.ndarray]:
+ """
+ Note: assumes `compute_fk` has been called to set the context.
+ """
+ plant_context = self.plant.GetMyContextFromRoot(self.context)
+ # Computes spatial velocity (so(3)xR^3) from joint velocities of the foot w.r.t the imu frame.
+ J_analyitical_map = {}
+
+ for name, frame in self.end_effector_frame_map.items():
+ J_analyitical_map[name] = self.plant.CalcJacobianSpatialVelocity(
+ plant_context,
+ JacobianWrtVariable.kQDot,
+ frame,
+ self.end_effector_offset_map[name],
+ self.imu_frame,
+ self.imu_frame,
+ )
+ return J_analyitical_map
+
+ def compute_kinematics(self, joint_positions: np.ndarray, joint_covariance: np.ndarray) -> dict[str, Kinematics]:
+ ee_transform_map = self.compute_fk(joint_positions=joint_positions)
+ analytical_jacobian_map = self.compute_analytical_jacobians()
+
+ kinematics_map = {}
+ for ee_name in ee_transform_map:
+ kinematic_covariance = analytical_jacobian_map[ee_name] @ joint_covariance @ analytical_jacobian_map[ee_name].T
+ kinematics_map[ee_name] = Kinematics(
+ id_in=self.end_effector_frame_name_to_id_map[ee_name],
+ pose_in=ee_transform_map[ee_name],
+ covariance_in=kinematic_covariance
+ )
+ return kinematics_map
diff --git a/playground/common/contact_aided_invariant_ekf/kinematics_example.py b/playground/common/contact_aided_invariant_ekf/kinematics_example.py
new file mode 100644
index 0000000..cdc57e6
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/kinematics_example.py
@@ -0,0 +1,204 @@
+import numpy as np
+import cProfile
+import pstats
+from matplotlib import pyplot as plt
+from playground.common.contact_aided_invariant_ekf.robot_state import RobotState
+from playground.common.contact_aided_invariant_ekf.noise_params import NoiseParams
+from playground.common.contact_aided_invariant_ekf.contact_aided_invariant_ekf import RightInEKF, Kinematics
+
+np.set_printoptions(precision=5, linewidth=100)
+
+# Conversion from string to numeric
+def stod98(s):
+ return float(s)
+
+
+def stoi98(s):
+ return int(stod98(s))
+
+
+def load_matrices_from_binary(filename):
+ """
+ Some reason this gets transposed when it comes in.
+ """
+ matrices = []
+ with open(filename, "rb") as f:
+ while True:
+ timestep_data = f.read(4)
+ if not timestep_data:
+ break # EOF
+
+ timestep = np.frombuffer(timestep_data, dtype=np.int32)[0]
+ rows = np.frombuffer(f.read(4), dtype=np.int32)[0]
+ cols = np.frombuffer(f.read(4), dtype=np.int32)[0]
+ data = np.frombuffer(f.read(rows * cols * 8), dtype=np.float64)
+
+ matrices.append((timestep, data.reshape((rows, cols)).T))
+
+ return matrices
+
+
+# Main function
+def main():
+ # ---- Initialize invariant extended Kalman filter ----- //
+ initial_state = RobotState()
+
+ # Initialize state mean
+ R0 = np.array([[1, 0, 0],
+ [0, -1, 0],
+ [0, 0, -1]])
+ v0 = np.zeros(3)
+ p0 = np.zeros(3)
+ bg0 = np.zeros(3)
+ ba0 = np.zeros(3)
+ initial_state.set_rotation(R0)
+ initial_state.set_velocity(v0)
+ initial_state.set_position(p0)
+ initial_state.set_gyroscope_bias(bg0)
+ initial_state.set_accelerometer_bias(ba0)
+
+ # Initialize state covariance
+ noise_params = NoiseParams(
+ gyroscope_nosie=0.01,
+ accelerometer_noise=0.1,
+ gyroscope_bias_noise=0.00001,
+ accelerometer_bias_noise=0.0001,
+ contact_noise=0.01
+ )
+
+ # Initialize filter
+ filter = RightInEKF(initial_state, noise_params)
+ # print("Noise parameters are initialized to:")
+ # print(filter.get_noise_params())
+ # print("Robot's state is initialized to:")
+ # print(filter.get_state())
+
+ # Open data file
+ data_file = "./playground/common/contact_aided_invariant_ekf/data/imu_kinematic_measurements.txt"
+ validation_data_file = "./playground/common/contact_aided_invariant_ekf/data/robot_state_estimates.bin"
+ kinematic_covariance_data_file = "./playground/common/contact_aided_invariant_ekf/data/kinematic_covariance_updates.bin"
+ prop_covariance_data_file = "./playground/common/contact_aided_invariant_ekf/data/propagation_updates.bin"
+ imu_measurement_prev = np.zeros(6)
+ t_prev = 0
+ count = 0
+ kinematic_count = 0
+ prop_count = 0
+
+ matrices = load_matrices_from_binary(validation_data_file)
+ kinematic_matrices = load_matrices_from_binary(kinematic_covariance_data_file)
+ propagation_matrices = load_matrices_from_binary(prop_covariance_data_file)
+ # ---- Loop through data file and read in measurements line by line ---- //
+ # TODO: debug propagation step at count 636. Seems like after adding a contact, it doesn't update properly.
+ error_list = []
+ contact_list = []
+ propagation_computation_time_list = []
+ with open(data_file, 'r') as infile:
+ for line in infile:
+ measurement = line.split()
+ # print(f"Count: {count}")
+ # # print("X: ", filter.get_state())
+ actual_state = filter.get_state()
+ # Load and print matrices
+ adjusted_idx = count * 3
+ validation_X = matrices[adjusted_idx][1]
+ validation_Theta = matrices[adjusted_idx + 1][1]
+ validation_P = matrices[adjusted_idx + 2][1]
+
+ # # print("Validation X: ", validation_X)
+
+ error_X = actual_state.get_x() - validation_X
+ error_P = actual_state.get_p() - validation_P
+ # # print("Error X: ", error_X)
+ # # print("Error P: ", error_P)
+
+ norm_error_X = np.linalg.norm(error_X)
+ norm_error_P = np.linalg.norm(error_P, axis=1)
+ # print("Norm Error X: ", norm_error_X)
+ # print("Norm Error P: ", norm_error_P)
+ error_list.append(norm_error_X)
+ count += 1
+
+ if measurement[0] == "IMU":
+ # print("Received IMU Data, propagating state")
+ assert len(measurement) - 2 == 6
+ t = stod98(measurement[1])
+ imu_measurement = np.array([stod98(x) for x in measurement[2:8]])
+
+ # Propagate using IMU data
+ dt = t - t_prev
+ if 1e-6 < dt < 1:
+ filter.propagate(imu_measurement_prev, dt)
+ # propagation_computation_time_list.append()
+ elif measurement[0] == "CONTACT":
+ # print("Received CONTACT Data, setting filter's contact state")
+ assert (len(measurement) - 2) % 2 == 0
+ contacts = []
+ t = stod98(measurement[1])
+ for i in range(2, len(measurement), 2):
+ id = stoi98(measurement[i])
+ indicator = bool(stod98(measurement[i + 1]))
+ if indicator:
+ pass
+ contacts.append((id, indicator))
+ filter.set_contacts(contacts)
+ contact_list.append((count, contacts[0][1], contacts[1][1]))
+ # # print("Set contacts: ",filter.contacts_)
+ elif measurement[0] == "KINEMATIC":
+ # print("Received KINEMATIC observation, correcting state")
+ assert (len(measurement) - 2) % 44 == 0
+ measured_kinematics = []
+ t = stod98(measurement[1])
+ # TODO: need to do the computations for Jacobians and covariance computations from them.
+ for i in range(2, len(measurement), 44):
+ id = stoi98(measurement[i])
+ q = np.array([stod98(measurement[i+j]) for j in range(1, 5)])
+ q = q / np.linalg.norm(q) # Normalize quaternion
+ p = np.array([stod98(measurement[i + 5]), stod98(measurement[i + 6]), stod98(measurement[i + 7])])
+ pose = np.eye(4)
+ pose[:3, :3] = q_to_rotation_matrix(q) # Assuming a function q_to_rotation_matrix exists
+ pose[:3, 3] = p
+ covariance = np.array([[stod98(measurement[i + 8 + j * 6 + k]) for k in range(6)] for j in range(6)])
+ # print("Kinematic pose: ", pose)
+ # print("Kinematic cov: ", covariance)
+ measured_kinematics.append(
+ Kinematics(id_in=id, pose_in=pose, covariance_in=covariance)
+ )
+ filter.correct_kinematics(measured_kinematics)
+
+ # Store previous timestamp
+ t_prev = t
+ imu_measurement_prev = imu_measurement
+ error_array = np.array(error_list)
+ contact_count_array = np.array([contact_tuple[0] for contact_tuple in contact_list])
+ contact_array = np.array([[contact_tuple[1], contact_tuple[2]] for contact_tuple in contact_list], dtype=float)
+ contact_array *= np.max(error_array) / 2
+ # plt.plot(error_list, label="State Error")
+ # plt.plot(contact_count_array, contact_array[:,0], label="Contact 0")
+ # plt.plot(contact_count_array, contact_array[:,1], label="Contact 1")
+ # plt.legend()
+ # plt.show()
+ # Print final state
+ print(filter.get_state())
+
+
+def q_to_rotation_matrix(q):
+ # TODO: use scipy?
+ # Assuming q is a normalized quaternion
+ w, x, y, z = q
+ return np.array([[1 - 2 * y**2 - 2 * z**2, 2 * x * y - 2 * w * z, 2 * x * z + 2 * w * y],
+ [2 * x * y + 2 * w * z, 1 - 2 * x**2 - 2 * z**2, 2 * y * z - 2 * w * x],
+ [2 * x * z - 2 * w * y, 2 * y * z + 2 * w * x, 1 - 2 * x**2 - 2 * y**2]])
+
+
+if __name__ == "__main__":
+ main()
+ # cProfile.run("main()")
+
+ # stats = pstats.Stats(pr)
+ # stats.strip_dirs().sort_stats("cumulative").print_stats(20) # Top 20 cumulative time
+
+ # pr = cProfile.Profile()
+ # pr.enable()
+ # main()
+ # pr.disable()
+ # pr.print_stats(sort="cumulative").print_stats(10)
\ No newline at end of file
diff --git a/playground/common/contact_aided_invariant_ekf/lie_group.py b/playground/common/contact_aided_invariant_ekf/lie_group.py
new file mode 100644
index 0000000..ff3536b
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/lie_group.py
@@ -0,0 +1,92 @@
+import numpy as np
+from playground.common.contact_aided_invariant_ekf.utils import CARTESIAN_DIM
+
+TOLERANCE = 1e-10
+SMALL_ANGLE_APPROXIMATION = 1e-6
+
+
+def skew(v: np.ndarray) -> np.ndarray:
+ """
+ Convert a 3D vector to a skew-symmetric matrix
+ If v has shape (3, N), returns (N, 3, 3) batch of skew-symmetric matrices.
+ """
+ v = np.asarray(v).squeeze() # Ensure it's at least 1D
+
+ if v.shape == (3,):
+ v = v[:, None] # Convert to (3,1) for consistent indexing
+
+ if v.shape[0] != 3:
+ raise ValueError(f"Input must have shape (3,), (3, N), or (N,3), but got {v.shape}")
+
+ if v.ndim == 1: # Single 3D vector case
+ return np.array([[0, -v[2], v[1]],
+ [v[2], 0, -v[0]],
+ [-v[1], v[0], 0]])
+
+ if v.shape[1] == 3: # Handle (N,3) case by transposing
+ v = v.T
+
+ N = v.shape[1] # Number of vectors
+ skew_matrices = np.zeros((N, 3, 3))
+
+ skew_matrices[:, 0, 1] = -v[2] # -z
+ skew_matrices[:, 0, 2] = v[1] # y
+ skew_matrices[:, 1, 0] = v[2] # z
+ skew_matrices[:, 1, 2] = -v[0] # -x
+ skew_matrices[:, 2, 0] = -v[1] # -y
+ skew_matrices[:, 2, 1] = v[0] # x
+
+ return skew_matrices[0] if N == 1 else skew_matrices # Return (3,3) if input was a single vector
+
+
+def exp_so3(w: np.ndarray) -> np.ndarray:
+ """ Computes the vectorized exponential map for SO(3) """
+ A = skew(w)
+ theta = np.linalg.norm(w)
+ if theta < TOLERANCE:
+ return np.eye(CARTESIAN_DIM)
+ elif theta < SMALL_ANGLE_APPROXIMATION:
+ return np.eye(CARTESIAN_DIM) + A
+ return np.eye(CARTESIAN_DIM) + (np.sin(theta)/theta) * A + ((1 - np.cos(theta)) / (theta**2)) * np.dot(A, A)
+
+
+def exp_sek3(v: np.ndarray) -> np.ndarray:
+ """ Computes the vectorized exponential map for SE_K(3) """
+ K = (len(v) - CARTESIAN_DIM) // CARTESIAN_DIM
+ X = np.eye(CARTESIAN_DIM + K)
+ w = v[:CARTESIAN_DIM]
+ theta = np.linalg.norm(w)
+ identity = np.eye(CARTESIAN_DIM)
+
+ if theta < TOLERANCE:
+ R = identity
+ Jl = identity
+ else:
+ A = skew(w)
+ theta2 = theta ** 2
+ stheta = np.sin(theta)
+ ctheta = np.cos(theta)
+ one_minus_cos_theta2 = (1 - ctheta) / theta2
+ A2 = np.dot(A, A)
+ R = identity + (stheta / theta) * A + one_minus_cos_theta2 * A2
+ Jl = identity + one_minus_cos_theta2 * A + ((theta - stheta) / (theta2 * theta)) * A2
+
+ X[:CARTESIAN_DIM, :CARTESIAN_DIM] = R
+ for i in range(K):
+ X[:CARTESIAN_DIM, CARTESIAN_DIM + i] = np.dot(Jl, v[CARTESIAN_DIM + CARTESIAN_DIM * i: 2*CARTESIAN_DIM + CARTESIAN_DIM * i])
+
+ return X
+
+
+def adjoint_sek3(X: np.ndarray) -> np.ndarray:
+ """ Compute Adjoint(X) for X in SE_K(3) """
+ K = X.shape[1] - CARTESIAN_DIM
+ Adj = np.zeros((CARTESIAN_DIM + CARTESIAN_DIM * K, CARTESIAN_DIM + CARTESIAN_DIM * K))
+ R = X[:CARTESIAN_DIM, :CARTESIAN_DIM]
+ Adj[:CARTESIAN_DIM, :CARTESIAN_DIM] = R
+
+ for i in range(K):
+ Adj[CARTESIAN_DIM + CARTESIAN_DIM * i: 6 + CARTESIAN_DIM * i, CARTESIAN_DIM + CARTESIAN_DIM * i: 6 + CARTESIAN_DIM * i] = R
+ Adj[CARTESIAN_DIM + CARTESIAN_DIM * i: 6 + CARTESIAN_DIM * i, :CARTESIAN_DIM] = np.dot(skew(X[:CARTESIAN_DIM, CARTESIAN_DIM + i]), R)
+
+ return Adj
\ No newline at end of file
diff --git a/playground/common/contact_aided_invariant_ekf/noise_params.py b/playground/common/contact_aided_invariant_ekf/noise_params.py
new file mode 100644
index 0000000..aca4c86
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/noise_params.py
@@ -0,0 +1,114 @@
+import numpy as np
+
+
+class NoiseParams:
+ def __init__(
+ self,
+ gyroscope_nosie: float = 0.01,
+ accelerometer_noise: float = 0.1,
+ gyroscope_bias_noise: float = 0.00001,
+ accelerometer_bias_noise: float = 0.0001,
+ landmark_noise: float = 0.1,
+ contact_noise: float = 0.1,
+ ):
+ # Default Constructor
+ self.set_gyroscope_noise(gyroscope_nosie)
+ self.set_accelerometer_noise(accelerometer_noise)
+ self.set_gyroscope_bias_noise(gyroscope_bias_noise)
+ self.set_accelerometer_bias_noise(accelerometer_bias_noise)
+ self.set_landmark_noise(landmark_noise)
+ self.set_contact_noise(contact_noise)
+
+ def set_gyroscope_noise(self, std):
+ self.Qg = std * std * np.identity(3)
+
+ def set_gyroscope_noise_vector(self, std):
+ self.Qg = np.array([[std[0] * std[0], 0, 0],
+ [0, std[1] * std[1], 0],
+ [0, 0, std[2] * std[2]]])
+
+ def set_gyroscope_noise_matrix(self, cov):
+ self.Qg = cov
+
+ def set_accelerometer_noise(self, std):
+ self.Qa = std * std * np.identity(3)
+
+ def set_accelerometer_noise_vector(self, std):
+ self.Qa = np.array([[std[0] * std[0], 0, 0],
+ [0, std[1] * std[1], 0],
+ [0, 0, std[2] * std[2]]])
+
+ def set_accelerometer_noise_matrix(self, cov):
+ self.Qa = cov
+
+ def set_gyroscope_bias_noise(self, std):
+ self.Qbg = std * std * np.identity(3)
+
+ def set_gyroscope_bias_noise_vector(self, std):
+ self.Qbg = np.array([[std[0] * std[0], 0, 0],
+ [0, std[1] * std[1], 0],
+ [0, 0, std[2] * std[2]]])
+
+ def set_gyroscope_bias_noise_matrix(self, cov):
+ self.Qbg = cov
+
+ def set_accelerometer_bias_noise(self, std):
+ self.Qba = std * std * np.identity(3)
+
+ def set_accelerometer_bias_noise_vector(self, std):
+ self.Qba = np.array([[std[0] * std[0], 0, 0],
+ [0, std[1] * std[1], 0],
+ [0, 0, std[2] * std[2]]])
+
+ def set_accelerometer_bias_noise_matrix(self, cov):
+ self.Qba = cov
+
+ def set_landmark_noise(self, std):
+ self.Ql = std * std * np.identity(3)
+
+ def set_landmark_noise_vector(self, std):
+ self.Ql = np.array([[std[0] * std[0], 0, 0],
+ [0, std[1] * std[1], 0],
+ [0, 0, std[2] * std[2]]])
+
+ def set_landmark_noise_matrix(self, cov):
+ self.Ql = cov
+
+ def set_contact_noise(self, std):
+ self.Qc = std * std * np.identity(3)
+
+ def set_contact_noise_vector(self, std):
+ self.Qc = np.array([[std[0] * std[0], 0, 0],
+ [0, std[1] * std[1], 0],
+ [0, 0, std[2] * std[2]]])
+
+ def set_contact_noise_matrix(self, cov):
+ self.Qc = cov
+
+ def get_gyroscope_cov(self):
+ return self.Qg
+
+ def get_accelerometer_cov(self):
+ return self.Qa
+
+ def get_gyroscope_bias_cov(self):
+ return self.Qbg
+
+ def get_accelerometer_bias_cov(self):
+ return self.Qba
+
+ def get_landmark_cov(self):
+ return self.Ql
+
+ def get_contact_cov(self):
+ return self.Qc
+
+ def __str__(self):
+ return (f"--------- Noise Params -------------\n"
+ f"Gyroscope Covariance:\n{self.Qg}\n"
+ f"Accelerometer Covariance:\n{self.Qa}\n"
+ f"Gyroscope Bias Covariance:\n{self.Qbg}\n"
+ f"Accelerometer Bias Covariance:\n{self.Qba}\n"
+ f"Landmark Covariance:\n{self.Ql}\n"
+ f"Contact Covariance:\n{self.Qc}\n"
+ f"-----------------------------------")
diff --git a/playground/common/contact_aided_invariant_ekf/observation.py b/playground/common/contact_aided_invariant_ekf/observation.py
new file mode 100644
index 0000000..cad1064
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/observation.py
@@ -0,0 +1,32 @@
+import numpy as np
+
+
+def check_measurement_is_empty(Y: np.ndarray):
+ return Y.shape[0] == 0
+
+
+class Observation:
+ def __init__(
+ self, Y: np.ndarray,
+ b: np.ndarray,
+ H: np.ndarray,
+ N: np.ndarray,
+ PI: np.ndarray
+ ):
+ self.Y = Y
+ self.b = b
+ self.H = H
+ self.N = N
+ self.PI = PI
+
+ def is_empty(self):
+ return check_measurement_is_empty(self.Y)
+
+ def __str__(self):
+ return ("---------- Observation ------------\n"
+ f"Y:\n{self.Y}\n\n"
+ f"b:\n{self.b}\n\n"
+ f"H:\n{self.H}\n\n"
+ f"N:\n{self.N}\n\n"
+ f"PI:\n{self.PI}\n"
+ "-----------------------------------")
\ No newline at end of file
diff --git a/playground/common/contact_aided_invariant_ekf/robot_kinematics.py b/playground/common/contact_aided_invariant_ekf/robot_kinematics.py
new file mode 100644
index 0000000..d6d01c9
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/robot_kinematics.py
@@ -0,0 +1,32 @@
+import numpy as np
+from typing import Callable
+
+
+class Kinematics:
+ def __init__(self, id_in: int, pose_in: np.ndarray, covariance_in: np.ndarray):
+ """
+ Kinematics class to store kinematic measurements and their covariance.
+
+ Parameters:
+ - id_in (int): Identifier for the measurement.
+ - pose_in (np.ndarray): 4x4 transformation matrix computed by Kinematics.
+ - covariance_in (np.ndarray): 6x6 covariance matrix computed by the corresponding Kinematic Jacobian.
+ """
+ assert pose_in.shape == (4, 4), "Pose must be a 4x4 matrix."
+ assert covariance_in.shape == (6, 6), "Covariance must be a 6x6 matrix."
+
+ self.id = id_in
+ self.pose = pose_in
+ self.covariance = covariance_in
+
+
+def compute_kinematics_covariance(
+ joint_positions: np.ndarray,
+ contact_cov: np.ndarray,
+ body_jacobian_functor: Callable[[np.ndarray], np.ndarray]
+) -> np.ndarray:
+ """
+ Note: errors have been defined with right-invariance (meaning body expressed in the body frame). Therefore, we need the body Jacobian of SE(3).
+ """
+ body_jacobian = body_jacobian_functor(joint_positions)
+ return body_jacobian @ contact_cov @ body_jacobian.T
\ No newline at end of file
diff --git a/playground/common/contact_aided_invariant_ekf/robot_state.py b/playground/common/contact_aided_invariant_ekf/robot_state.py
new file mode 100644
index 0000000..2d1b21d
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/robot_state.py
@@ -0,0 +1,125 @@
+import numpy as np
+from typing import Optional
+from playground.common.contact_aided_invariant_ekf.utils import CARTESIAN_DIM, RIGID_TRANSFORM_SIZE
+
+
+def set_array_w_different_shape(
+ array_to_set: np.ndarray,
+ array_w_different_shape: np.ndarray
+):
+ return np.reshape(array_w_different_shape, array_to_set.shape)
+
+
+class RobotState:
+ """
+ Robot state
+ X = [R_WB, v_B, p_WB, p_C1, p_C2]
+ P = Covariance
+ """
+ def __init__(
+ self,
+ X: Optional[np.ndarray] = None,
+ Theta: Optional[np.ndarray] = None,
+ P: Optional[np.ndarray] = None
+ ):
+ if X is None:
+ X = np.eye(5)
+ if Theta is None:
+ Theta = np.zeros((2*CARTESIAN_DIM, 1))
+
+ self.X_ = X
+ self.Theta_ = Theta
+
+ if P is None:
+ P = np.eye(CARTESIAN_DIM * self.dim_x() + self.dim_theta() - 2*CARTESIAN_DIM)
+
+ self.P_ = P
+
+ def get_x(self) -> np.ndarray:
+ return self.X_.copy()
+
+ def get_theta(self) -> np.ndarray:
+ return self.Theta_.copy()
+
+ def get_p(self) -> np.ndarray:
+ return self.P_.copy()
+
+ def get_rotation(self) -> np.ndarray:
+ return self.X_[:CARTESIAN_DIM, :CARTESIAN_DIM].copy()
+
+ def get_velocity(self) -> np.ndarray:
+ return self.X_[:CARTESIAN_DIM, CARTESIAN_DIM].copy()
+
+ def get_position(self) -> np.ndarray:
+ return self.X_[:CARTESIAN_DIM, RIGID_TRANSFORM_SIZE].copy()
+
+ def get_gyroscope_bias(self) -> np.ndarray:
+ return self.Theta_[:CARTESIAN_DIM].copy()
+
+ def get_accelerometer_bias(self) -> np.ndarray:
+ return self.Theta_[-CARTESIAN_DIM:].copy()
+
+ def dim_x(self) -> np.ndarray:
+ return self.X_.shape[1]
+
+ def dim_theta(self) -> np.ndarray:
+ return self.Theta_.shape[0]
+
+ def dim_p(self) -> np.ndarray:
+ return self.P_.shape[1]
+
+ def set_x(self, X: np.ndarray):
+ self.X_ = X
+
+ def set_theta(self, Theta: np.ndarray):
+ self.Theta_ = Theta
+
+ def set_p(self, P: np.ndarray):
+ self.P_ = P
+
+ def set_rotation(self, R: np.ndarray):
+ self.X_[:CARTESIAN_DIM, :CARTESIAN_DIM] = R.copy()
+
+ def set_velocity(self, v: np.ndarray):
+ self.X_[:CARTESIAN_DIM, CARTESIAN_DIM] = v.reshape(
+ self.X_[:CARTESIAN_DIM, CARTESIAN_DIM].shape
+ ).copy()
+
+ def set_position(self, p: np.ndarray):
+ self.X_[:CARTESIAN_DIM, CARTESIAN_DIM + 1] = p.reshape(
+ self.X_[:CARTESIAN_DIM, CARTESIAN_DIM + 1].shape
+ ).copy()
+
+ def set_gyroscope_bias(self, bg: np.ndarray):
+ bg = self.Theta_[:CARTESIAN_DIM] = bg.reshape(
+ self.Theta_[:CARTESIAN_DIM].shape
+ )
+
+ def set_accelerometer_bias(self, ba: np.ndarray):
+ ba = ba.reshape(
+ self.Theta_[-CARTESIAN_DIM:].shape
+ )
+
+ def copy_diag_x(self, n):
+ """
+ Create a block diagonal matrix with X as the diagonal elements.
+ """
+ dimX = self.dim_x()
+
+ # Create a list of n identity blocks of size (dimX, dimX)
+ blocks = [np.eye(dimX) for _ in range(n)]
+
+ # Create a list of `X_` blocks along the diagonal
+ blocks = [self.X_ if i == j else np.zeros((dimX, dimX)) for i in range(n) for j in range(n)]
+
+ # Reshape into a (n, n) structure and use np.block to assemble the matrix
+ BigX = np.block([[blocks[i * n + j] for j in range(n)] for i in range(n)])
+
+ return BigX
+
+ def __str__(self) -> str:
+ return ("--------- Robot State -------------\n"
+ f"X:\n{self.X_}\n\n"
+ f"Theta:\n{self.Theta_}\n\n"
+ f"P:\n{self.P_}\n"
+ "-----------------------------------")
\ No newline at end of file
diff --git a/playground/common/contact_aided_invariant_ekf/utils.py b/playground/common/contact_aided_invariant_ekf/utils.py
new file mode 100644
index 0000000..ca731f7
--- /dev/null
+++ b/playground/common/contact_aided_invariant_ekf/utils.py
@@ -0,0 +1,18 @@
+import numpy as np
+CARTESIAN_DIM = 3
+RIGID_TRANSFORM_SIZE = 4
+GRAVITY_ACCELERATION = -9.81
+
+
+def remove_row_and_column(M, index):
+ # dim_x = M.shape[1]
+ # # Print statement for debugging (similar to the C++ code)
+ # # print(f"Removing index: {index}")
+
+ # Remove the row
+ M = np.delete(M, index, axis=0)
+
+ # Remove the column
+ M = np.delete(M, index, axis=1)
+
+ return M
diff --git a/playground/common/export_onnx.py b/playground/common/export_onnx.py
index a1c445f..170b534 100644
--- a/playground/common/export_onnx.py
+++ b/playground/common/export_onnx.py
@@ -147,7 +147,7 @@ def transfer_weights(jax_params, tf_model):
print("Weights transferred successfully.")
- transfer_weights(params[1].policy["params"], tf_policy_network)
+ transfer_weights(params[1]["params"], tf_policy_network)
# Example inputs for the model
test_input = [np.ones((1, obs_size), dtype=np.float32)]
diff --git a/playground/common/poly_reference_motion.py b/playground/common/poly_reference_motion.py
index 62326af..d26311a 100644
--- a/playground/common/poly_reference_motion.py
+++ b/playground/common/poly_reference_motion.py
@@ -174,14 +174,15 @@ def get_reference_motion(self, dx, dy, dtheta, i):
"playground/open_duck_mini_v2/data/polynomial_coefficients.pkl"
)
vals = []
- select_dim = -1
- for i in range(PRM.nb_steps_in_period):
- vals.append(PRM.get_reference_motion(0.0, -0.05, -0.1, i)[select_dim])
+ total = 10 * PRM.nb_steps_in_period
+ # select_dim =
+ for i in range(total):
+ vals.append(PRM.get_reference_motion(-0.05, -0.0, -0.0, i)[34]) # 32
# plot
import matplotlib.pyplot as plt
import numpy as np
- ts = np.arange(0, PRM.nb_steps_in_period)
+ ts = np.arange(0, total)
plt.plot(ts, vals)
plt.show()
diff --git a/playground/open_duck_mini_v2/custom_rewards.py b/playground/open_duck_mini_v2/custom_rewards.py
index 018e42c..123904a 100644
--- a/playground/open_duck_mini_v2/custom_rewards.py
+++ b/playground/open_duck_mini_v2/custom_rewards.py
@@ -138,7 +138,7 @@ def reward_imitation(
lin_vel_xy_rew
+ lin_vel_z_rew
+ ang_vel_xy_rew
- + ang_vel_z_rew
+ # + ang_vel_z_rew
+ joint_pos_rew
+ joint_vel_rew
+ contact_rew
diff --git a/playground/open_duck_mini_v2/joystick.py b/playground/open_duck_mini_v2/joystick.py
index 6e98371..00d31b3 100644
--- a/playground/open_duck_mini_v2/joystick.py
+++ b/playground/open_duck_mini_v2/joystick.py
@@ -47,6 +47,47 @@
USE_MOTOR_SPEED_LIMITS = True
+def quat_to_rot_matrix(q: jp.array):
+ """Assumes input quaternion is [w, x, y, z]"""
+ w, x, y, z = q
+
+ # Normalize quaternion to ensure proper rotation matrix
+ norm = jp.sqrt(w**2 + x**2 + y**2 + z**2)
+ w, x, y, z = w / norm, x / norm, y / norm, z / norm
+
+ return jp.array([
+ [1 - 2*y**2 - 2*z**2, 2*x*y - 2*z*w, 2*x*z + 2*y*w],
+ [2*x*y + 2*z*w, 1 - 2*x**2 - 2*z**2, 2*y*z - 2*x*w],
+ [2*x*z - 2*y*w, 2*y*z + 2*x*w, 1 - 2*x**2 - 2*y**2]
+ ])
+
+def axis_angle_to_rotation(axis_angle: jp.ndarray) -> jp.ndarray:
+ """
+ Converts an axis-angle vector to a rotation matrix using Rodrigues' formula.
+
+ Args:
+ axis_angle: jp.ndarray of shape (3,), representing axis * angle
+
+ Returns:
+ A 3x3 rotation matrix as a jnp.ndarray
+ """
+ theta = jp.linalg.norm(axis_angle)
+ def zero_rotation():
+ return jp.eye(3)
+
+ def nonzero_rotation():
+ axis = axis_angle / theta
+ x, y, z = axis
+ K = jp.array([[ 0, -z, y],
+ [ z, 0, -x],
+ [ -y, x, 0]])
+ I = jp.eye(3)
+ R = I + jp.sin(theta) * K + (1 - jp.cos(theta)) * (K @ K)
+ return R
+
+ return jax.lax.cond(theta < 1e-6, zero_rotation, nonzero_rotation)
+
+
def default_config() -> config_dict.ConfigDict:
return config_dict.create(
ctrl_dt=0.02,
@@ -76,6 +117,7 @@ def default_config() -> config_dict.ConfigDict:
linvel=0.1,
gyro=0.1,
accelerometer=0.05,
+ rotation = np.pi/12,
),
),
reward_config=config_dict.create(
@@ -207,6 +249,19 @@ def _post_init(self) -> None:
# self.action_filter = LowPassActionFilter(
# 1 / self._config.ctrl_dt, cutoff_frequency=37.5
# )
+ self.imu_id = self._mj_model.body("imu").id
+ self.feet_ids = {
+ 0: self._mj_model.body("foot_assembly").id,
+ 1: self._mj_model.body("foot_assembly_2").id,
+ }
+
+ def get_pose_from_id(self, data, id: str) -> jp.ndarray:
+ pos = data.xpos[id]
+ quat = data.xquat[id]
+ pose = jp.eye(4)
+ pose = pose.at[:3, :3].set(quat_to_rot_matrix(quat))
+ pose = pose.at[:3, 3].set(pos)
+ return pose
def reset(self, rng: jax.Array) -> mjx_env.State:
qpos = self._init_q # the complete qpos
@@ -598,11 +653,40 @@ def _get_obs(
# * self._config.noise_config.scales.linvel
# )
+ # TODO add noise.
+ imu_pose_world = self.get_pose_from_id(data, self.imu_id)
+ rotation_world = imu_pose_world[0:3, 0:3]
+ translation_world = imu_pose_world[0:3, 3]
+
+ info["rng"], noise_rng = jax.random.split(info["rng"])
+ rotation_noise = (
+ (2.0 * jax.random.uniform(noise_rng, shape=(3,)) - 1.0)
+ * self._config.noise_config.level
+ * self._config.noise_config.scales.rotation
+ )
+
+ noisy_rotation_world = axis_angle_to_rotation(rotation_noise) @ rotation_world
+ noisy_rotation_world_6d = noisy_rotation_world[:, 0:2].flatten()
+
+ floating_base_vel_world = data.qvel[self._floating_base_qvel_addr:self._floating_base_qvel_addr + 6]
+ floating_base_vel_body = rotation_world.T @ floating_base_vel_world[0:3]
+
+ info["rng"], noise_rng = jax.random.split(info["rng"])
+ noisy_floating_base_vel_body = (
+ floating_base_vel_body
+ + (2.0 * jax.random.uniform(noise_rng, shape=jp.shape(floating_base_vel_body)) - 1.0)
+ * self._config.noise_config.level
+ * self._config.noise_config.scales.linvel
+ )
+
state = jp.hstack(
[
# noisy_linvel, # 3
# noisy_gyro, # 3
# noisy_gravity, # 3
+ noisy_rotation_world_6d,
+ # translation_world,
+ noisy_floating_base_vel_body,
noisy_gyro, # 3
noisy_accelerometer, # 3
info["command"], # 7
@@ -663,10 +747,17 @@ def _get_reward(
) -> dict[str, jax.Array]:
del metrics # Unused.
+ # Used to get linvel. lin vel sensor is not accurate.
+ imu_pose_world = self.get_pose_from_id(data, self.imu_id)
+ rotation_world = imu_pose_world[0:3, 0:3]
+ floating_base_vel_world = self.get_floating_base_qvel(data.qvel)
+ floating_base_vel_body = rotation_world.T @ floating_base_vel_world[0:3]
+
ret = {
"tracking_lin_vel": reward_tracking_lin_vel(
info["command"],
- self.get_local_linvel(data),
+ # self.get_local_linvel(data),
+ floating_base_vel_body,
self._config.reward_config.tracking_sigma,
),
"tracking_ang_vel": reward_tracking_ang_vel(
diff --git a/playground/open_duck_mini_v2/mujoco_infer.py b/playground/open_duck_mini_v2/mujoco_infer.py
index a27fb37..2ba56fa 100644
--- a/playground/open_duck_mini_v2/mujoco_infer.py
+++ b/playground/open_duck_mini_v2/mujoco_infer.py
@@ -6,6 +6,7 @@
import time
import argparse
from etils import epath
+from scipy.spatial.transform import Rotation as sp_R
from playground.common.onnx_infer import OnnxInfer
from playground.common.poly_reference_motion_numpy import PolyReferenceMotion
from playground.common.utils import LowPassActionFilter
@@ -13,12 +14,19 @@
# from playground.open_duck_mini_v2 import constants
from playground.open_duck_mini_v2 import base
+from playground.common.contact_aided_invariant_ekf.contact_aided_invariant_ekf import (
+ RightInEKF,
+)
+from playground.common.contact_aided_invariant_ekf.robot_state import RobotState
+from playground.common.contact_aided_invariant_ekf.noise_params import NoiseParams
+from playground.common.contact_aided_invariant_ekf.drake_kinematics import DrakeKinematics
+
USE_MOTOR_SPEED_LIMITS = True
class MjInfer:
def __init__(
- self, model_path: str, reference_data: str, onnx_model_path: str, standing: bool
+ self, model_path: str, reference_data: str, onnx_model_path: str, standing: bool, urdf_model_path: str
):
self.model = mujoco.MjModel.from_xml_string(
epath.Path(model_path).read_text(), assets=base.get_assets()
@@ -105,6 +113,10 @@ def __init__(
0
] # Assuming there is only one floating base! the jnt_type==0 is a floating joint. 3 is a hinge
+ self.actuator_name_to_idx_map = {
+ n: self.get_joint_addr_from_name(n) for n in self.actuator_names
+ }
+
self._floating_base_id = self.model.joint(self.floating_base_name).id
# self.all_joint_no_backlash_ids=np.zeros(7+self.model.nu)
@@ -187,6 +199,65 @@ def __init__(
print(f"backlash joint names: {self.backlash_joint_names}")
# print(f"actual joints idx: {self.get_actual_joints_idx()}")
+ # Gather body and feet id
+ self.imu_id = self.data.body("imu").id
+ self.feet_ids = {
+ 0: self.data.body("foot_assembly").id,
+ 1: self.data.body("foot_assembly_2").id,
+ }
+
+ # If unknown, set to identity.
+ initial_pose = self.get_pose_from_id(self.data, self.imu_id)
+
+ # Convert to rotation matrix
+ body_rotation_matrix = initial_pose[0:3, 0:3]
+ self.ekf_noise_params = NoiseParams() # TODO: put in real
+ # self.ekf_noise_params.set_gyroscope_bias_noise(1e-6)
+ # ekf_noise_params.set_contact_noise(0.5)
+ ekf_robot_state = RobotState()
+ ekf_robot_state.set_position(initial_pose[0:3, 3])
+ ekf_robot_state.set_rotation(body_rotation_matrix)
+ ekf_robot_state.set_velocity(np.zeros(3))
+ self._ekf = RightInEKF(ekf_robot_state, self.ekf_noise_params)
+
+ # Define the forward kinematics source.
+ self.drake_kinematics = DrakeKinematics(
+ imu_frame_name="imu",
+ urdf_model_path=urdf_model_path,
+ end_effector_frame_name_to_id_map={
+ "foot_assembly": 0,
+ "foot_assembly_2": 1,
+ },
+ # From URDF assembly to foot. And then add additional padding from foot link to bottom of foot.
+ end_effector_offset_map={
+ "foot_assembly": [0.0005, -0.036225 - 0.008, 0.01955],
+ "foot_assembly_2": [0.0005, -0.036225 - 0.008, 0.01955],
+ },
+ )
+
+ # Define the mapping from mujoco index to drake index
+ self.mask = np.zeros(
+ len(self.drake_kinematics.joint_name_to_idx_map), dtype=int
+ )
+ for name, idx in self.drake_kinematics.joint_name_to_idx_map.items():
+ self.mask[idx] = self.actuator_name_to_idx_map[name]
+
+ covariance_scaling_factor = 10.0 # Just using a random scaling term to sample initial biases. Then these covariances are used to do a random walk.
+ self.gyro_bias = np.random.multivariate_normal(np.zeros(3), covariance_scaling_factor*self.ekf_noise_params.get_gyroscope_bias_cov())
+ self.accelerometer_bias = np.random.multivariate_normal(np.zeros(3), covariance_scaling_factor*self.ekf_noise_params.get_accelerometer_bias_cov())
+
+ # grab initial sim time
+ self.prev_sim_time = self.data.time
+ self.ekf_imu_measurement_prev = np.zeros(6)
+
+ def get_pose_from_id(self, data, id: str) -> np.ndarray:
+ pos = data.xpos[id]
+ quat = data.xquat[id]
+ pose = np.eye(4)
+ pose[:3, :3] = sp_R.from_quat(quat, scalar_first=True).as_matrix()
+ pose[:3, 3] = pos
+ return pose
+
def get_actuator_id_from_name(self, name: str) -> int:
"""Return the id of a specified actuator"""
return mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_ACTUATOR, name)
@@ -341,6 +412,8 @@ def get_obs(
self,
data,
command, # , qvel_history, qpos_error_history, gravity_history
+ use_ekf: bool = False,
+ correct_kin: bool = False
):
gyro = self.get_gyro(data)
accelerometer = self.get_accelerometer(data)
@@ -355,8 +428,56 @@ def get_obs(
# if not self.standing:
# ref = self.PRM.get_reference_motion(*command[:3], self.imitation_i)
+ ekf_imu_measurement = np.zeros(6)
+ ekf_imu_measurement[0:3] = gyro
+ ekf_imu_measurement[3:6] = accelerometer
+
+ current_sim_time = data.time
+ elapsed_sim_time = current_sim_time - self.prev_sim_time
+ self._ekf.propagate(
+ self.ekf_imu_measurement_prev, # use previous measurement.
+ dt=elapsed_sim_time,
+ )
+
+ # Update prev sim time
+ self.prev_sim_time = current_sim_time
+
+ self.ekf_imu_measurement_prev = ekf_imu_measurement.copy()
+
+ ekf_contact_measurement = [(idx, contacts[idx]) for idx in range(len(contacts))]
+ self._ekf.set_contacts(ekf_contact_measurement)
+ joint_uncertainty = 1e-3
+ feet_to_kinematics_map = self.drake_kinematics.compute_kinematics(
+ data.qpos[self.mask],
+ joint_uncertainty * np.eye(len(joint_angles)),
+ )
+
+ if correct_kin:
+ self._ekf.correct_kinematics(
+ measured_kinematics=list(feet_to_kinematics_map.values())
+ )
+
+ estimated_state = self._ekf.get_state()
+
+ if not use_ekf:
+ imu_pose_world = self.get_pose_from_id(data, self.imu_id)
+ rotation_world = imu_pose_world[0:3, 0:3]
+ translation_world = imu_pose_world[0:3, 3]
+ floating_base_vel_world = data.qvel[self._floating_base_qvel_addr:self._floating_base_qvel_addr + 6]
+ else:
+ rotation_world = estimated_state.get_rotation()
+ translation_world = estimated_state.get_position()
+ floating_base_vel_world = estimated_state.get_velocity()
+
+
+ rotation_world_6d = rotation_world[:,0:2].flatten()
+ floating_base_vel_body = rotation_world.T @ floating_base_vel_world[0:3]
+
obs = np.concatenate(
- [
+ [
+ rotation_world_6d,
+ # translation_world,
+ floating_base_vel_body,
gyro,
accelerometer,
# gravity,
@@ -474,10 +595,12 @@ def run(self):
obs = self.get_obs(
self.data,
self.commands,
+ use_ekf=True,
+ correct_kin=True
)
-
- self.obs_history = np.roll(self.obs_history, 45)
- self.obs_history[:45] = obs
+ magic_number = 45 + 6 + 3 # 6d pose, lin vel
+ self.obs_history = np.roll(self.obs_history, magic_number)
+ self.obs_history[:magic_number] = obs
obs = self.obs_history
self.saved_obs.append(obs)
@@ -537,11 +660,16 @@ def run(self):
type=str,
default="playground/open_duck_mini_v2/xmls/scene_flat_terrain.xml",
)
+ parser.add_argument(
+ "--urdf_model_path",
+ type=str,
+ required=True
+ )
parser.add_argument("--standing", action="store_true", default=False)
args = parser.parse_args()
mjinfer = MjInfer(
- args.model_path, args.reference_data, args.onnx_model_path, args.standing
+ args.model_path, args.reference_data, args.onnx_model_path, args.standing, urdf_model_path = args.urdf_model_path
)
mjinfer.run()
diff --git a/playground/open_duck_mini_v2/urdfs/assets/antenna.part b/playground/open_duck_mini_v2/urdfs/assets/antenna.part
new file mode 100644
index 0000000..c4fa9d2
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/antenna.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MmXLbiyIJZ1T9tiX3",
+ "isStandardContent": false,
+ "name": "antenna <1>",
+ "partId": "RuOD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/antenna.stl b/playground/open_duck_mini_v2/urdfs/assets/antenna.stl
new file mode 100644
index 0000000..07eb706
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/antenna.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/battery_pack_lid.part b/playground/open_duck_mini_v2/urdfs/assets/battery_pack_lid.part
new file mode 100644
index 0000000..af53488
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/battery_pack_lid.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MvOQ01tQlVV+zSv63",
+ "isStandardContent": false,
+ "name": "battery_pack_lid <1>",
+ "partId": "R5OD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/battery_pack_lid.stl b/playground/open_duck_mini_v2/urdfs/assets/battery_pack_lid.stl
new file mode 100644
index 0000000..076eb25
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/battery_pack_lid.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/bms.part b/playground/open_duck_mini_v2/urdfs/assets/bms.part
new file mode 100644
index 0000000..d5e0fd2
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/bms.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "20dad50bf4a254b818c813f7",
+ "fullConfiguration": "default",
+ "id": "MqEGDvIKFH4SpUaCn",
+ "isStandardContent": false,
+ "name": "bms <1>",
+ "partId": "JSD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/bms.stl b/playground/open_duck_mini_v2/urdfs/assets/bms.stl
new file mode 100644
index 0000000..4598b81
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/bms.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/bno055.part b/playground/open_duck_mini_v2/urdfs/assets/bno055.part
new file mode 100644
index 0000000..31c1864
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/bno055.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "58e35a434b8265113623a1c6",
+ "fullConfiguration": "default",
+ "id": "MCK/voA1KPjJiuZRD",
+ "isStandardContent": false,
+ "name": "BNO055 <1>",
+ "partId": "JHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/bno055.stl b/playground/open_duck_mini_v2/urdfs/assets/bno055.stl
new file mode 100644
index 0000000..6de1ee7
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/bno055.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/board.part b/playground/open_duck_mini_v2/urdfs/assets/board.part
new file mode 100644
index 0000000..fd7767f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/board.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "fbc3ecd1071c724f4d859dd6",
+ "fullConfiguration": "default",
+ "id": "MxRZVYwGEp1Sig2/i",
+ "isStandardContent": false,
+ "name": "Board <1>",
+ "partId": "JFD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/board.stl b/playground/open_duck_mini_v2/urdfs/assets/board.stl
new file mode 100644
index 0000000..f2f3da5
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/board.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_back.part b/playground/open_duck_mini_v2/urdfs/assets/body_back.part
new file mode 100644
index 0000000..ddd0e80
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/body_back.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MfCA08JspCUYCoOzy",
+ "isStandardContent": false,
+ "name": "body_back <1>",
+ "partId": "RqKD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_back.stl b/playground/open_duck_mini_v2/urdfs/assets/body_back.stl
new file mode 100644
index 0000000..b6692ac
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/body_back.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_front.part b/playground/open_duck_mini_v2/urdfs/assets/body_front.part
new file mode 100644
index 0000000..9b9ab45
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/body_front.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MAILAHna+4EMDjwEB",
+ "isStandardContent": false,
+ "name": "body_front <1>",
+ "partId": "RbKD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_front.stl b/playground/open_duck_mini_v2/urdfs/assets/body_front.stl
new file mode 100644
index 0000000..fa76bb4
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/body_front.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_middle_bottom.part b/playground/open_duck_mini_v2/urdfs/assets/body_middle_bottom.part
new file mode 100644
index 0000000..fd48081
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/body_middle_bottom.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "Mi7/ZBgz7j8FhNN8n",
+ "isStandardContent": false,
+ "name": "body_middle_bottom <1>",
+ "partId": "R/KH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_middle_bottom.stl b/playground/open_duck_mini_v2/urdfs/assets/body_middle_bottom.stl
new file mode 100644
index 0000000..9c8ccee
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/body_middle_bottom.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_middle_top.part b/playground/open_duck_mini_v2/urdfs/assets/body_middle_top.part
new file mode 100644
index 0000000..e41d2c5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/body_middle_top.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MwLs2m7WqJdIp5rCM",
+ "isStandardContent": false,
+ "name": "body_middle_top <1>",
+ "partId": "R/KD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/body_middle_top.stl b/playground/open_duck_mini_v2/urdfs/assets/body_middle_top.stl
new file mode 100644
index 0000000..5530f0b
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/body_middle_top.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/cell.part b/playground/open_duck_mini_v2/urdfs/assets/cell.part
new file mode 100644
index 0000000..c7c9417
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/cell.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "20dad50bf4a254b818c813f7",
+ "fullConfiguration": "default",
+ "id": "Mx1gCi95bgVKmQGMH",
+ "isStandardContent": false,
+ "name": "cell <2>",
+ "partId": "JHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/cell.stl b/playground/open_duck_mini_v2/urdfs/assets/cell.stl
new file mode 100644
index 0000000..20e4cc3
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/cell.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/drive_palonier.part b/playground/open_duck_mini_v2/urdfs/assets/drive_palonier.part
new file mode 100644
index 0000000..52a07d3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/drive_palonier.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "d386542214948bc90a7bc881",
+ "fullConfiguration": "default",
+ "id": "MHjgEclEhEZQK/p6r",
+ "isStandardContent": false,
+ "name": "drive_palonier <1>",
+ "partId": "JJD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/drive_palonier.stl b/playground/open_duck_mini_v2/urdfs/assets/drive_palonier.stl
new file mode 100644
index 0000000..66e60e4
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/drive_palonier.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_pla.part b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_pla.part
new file mode 100644
index 0000000..d876e33
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_pla.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MbWaXbNFhwXrvfPr1",
+ "isStandardContent": false,
+ "name": "foot_bottom_pla <1>",
+ "partId": "R7GH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_pla.stl b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_pla.stl
new file mode 100644
index 0000000..66feed7
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_pla.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_tpu.part b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_tpu.part
new file mode 100644
index 0000000..6b37d3a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_tpu.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MSRJjnMROc2yqGlBV",
+ "isStandardContent": false,
+ "name": "foot_bottom_tpu <1>",
+ "partId": "R7GD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_tpu.stl b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_tpu.stl
new file mode 100644
index 0000000..4f05326
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/foot_bottom_tpu.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_side.part b/playground/open_duck_mini_v2/urdfs/assets/foot_side.part
new file mode 100644
index 0000000..b35a88b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/foot_side.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "M9QvdrmpVd96BQQ3J",
+ "isStandardContent": false,
+ "name": "foot_side <1>",
+ "partId": "RsGD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_side.stl b/playground/open_duck_mini_v2/urdfs/assets/foot_side.stl
new file mode 100644
index 0000000..20a434e
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/foot_side.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_top.part b/playground/open_duck_mini_v2/urdfs/assets/foot_top.part
new file mode 100644
index 0000000..44b9fc9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/foot_top.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MryNg763VjsN4xBWU",
+ "isStandardContent": false,
+ "name": "foot_top <1>",
+ "partId": "RsGH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/foot_top.stl b/playground/open_duck_mini_v2/urdfs/assets/foot_top.stl
new file mode 100644
index 0000000..0d08c19
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/foot_top.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head.part b/playground/open_duck_mini_v2/urdfs/assets/head.part
new file mode 100644
index 0000000..e377a37
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/head.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MGPnRRHSCLRuHbf9s",
+ "isStandardContent": false,
+ "name": "head <1>",
+ "partId": "RXMD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head.stl b/playground/open_duck_mini_v2/urdfs/assets/head.stl
new file mode 100644
index 0000000..2a101fd
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/head.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_bot_sheet.part b/playground/open_duck_mini_v2/urdfs/assets/head_bot_sheet.part
new file mode 100644
index 0000000..b0ce6c3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/head_bot_sheet.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MB88Zh5nm8uQRQJB5",
+ "isStandardContent": false,
+ "name": "head_bot_sheet <1>",
+ "partId": "RxMD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_bot_sheet.stl b/playground/open_duck_mini_v2/urdfs/assets/head_bot_sheet.stl
new file mode 100644
index 0000000..c565ba6
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/head_bot_sheet.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_pitch_to_yaw.part b/playground/open_duck_mini_v2/urdfs/assets/head_pitch_to_yaw.part
new file mode 100644
index 0000000..b3b7876
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/head_pitch_to_yaw.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MMYrJ8GU6Tulh9Ezl",
+ "isStandardContent": false,
+ "name": "head_pitch_to_yaw <1>",
+ "partId": "RGCD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_pitch_to_yaw.stl b/playground/open_duck_mini_v2/urdfs/assets/head_pitch_to_yaw.stl
new file mode 100644
index 0000000..1de8aef
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/head_pitch_to_yaw.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_roll_mount.part b/playground/open_duck_mini_v2/urdfs/assets/head_roll_mount.part
new file mode 100644
index 0000000..eef2d92
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/head_roll_mount.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MRmftgtax43WG3TM4",
+ "isStandardContent": false,
+ "name": "head_roll_mount <1>",
+ "partId": "RMND",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_roll_mount.stl b/playground/open_duck_mini_v2/urdfs/assets/head_roll_mount.stl
new file mode 100644
index 0000000..e6efec9
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/head_roll_mount.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_yaw_to_roll.part b/playground/open_duck_mini_v2/urdfs/assets/head_yaw_to_roll.part
new file mode 100644
index 0000000..8bf9328
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/head_yaw_to_roll.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MSSQrz89LHCpx23/c",
+ "isStandardContent": false,
+ "name": "head_yaw_to_roll <1>",
+ "partId": "RyCD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/head_yaw_to_roll.stl b/playground/open_duck_mini_v2/urdfs/assets/head_yaw_to_roll.stl
new file mode 100644
index 0000000..14a2122
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/head_yaw_to_roll.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/holder.part b/playground/open_duck_mini_v2/urdfs/assets/holder.part
new file mode 100644
index 0000000..cd32e37
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/holder.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "20dad50bf4a254b818c813f7",
+ "fullConfiguration": "default",
+ "id": "MhtdHOvIsBT6us1tg",
+ "isStandardContent": false,
+ "name": "holder <1>",
+ "partId": "JLD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/holder.stl b/playground/open_duck_mini_v2/urdfs/assets/holder.stl
new file mode 100644
index 0000000..0d3f382
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/holder.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_antenna_holder.part b/playground/open_duck_mini_v2/urdfs/assets/left_antenna_holder.part
new file mode 100644
index 0000000..da68d2a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/left_antenna_holder.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MqpShx/iKn+WMc6nz",
+ "isStandardContent": false,
+ "name": "left_antenna_holder <1>",
+ "partId": "RfPL",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_antenna_holder.stl b/playground/open_duck_mini_v2/urdfs/assets/left_antenna_holder.stl
new file mode 100644
index 0000000..5b20ae7
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/left_antenna_holder.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_cache.part b/playground/open_duck_mini_v2/urdfs/assets/left_cache.part
new file mode 100644
index 0000000..55d3efd
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/left_cache.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "Mh206kD+LDwOu9+3I",
+ "isStandardContent": false,
+ "name": "left_cache <1>",
+ "partId": "RELD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_cache.stl b/playground/open_duck_mini_v2/urdfs/assets/left_cache.stl
new file mode 100644
index 0000000..a927bc9
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/left_cache.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_left_sheet.part b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_left_sheet.part
new file mode 100644
index 0000000..3c6a790
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_left_sheet.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MkexR4anxdIDvoNnP",
+ "isStandardContent": false,
+ "name": "left_knee_to_ankle_left_sheet <1>",
+ "partId": "RyDD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_left_sheet.stl b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_left_sheet.stl
new file mode 100644
index 0000000..e46725d
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_left_sheet.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_right_sheet.part b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_right_sheet.part
new file mode 100644
index 0000000..e88575f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_right_sheet.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MFSYykuSOyFPl8MEE",
+ "isStandardContent": false,
+ "name": "left_knee_to_ankle_right_sheet <1>",
+ "partId": "RyDH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_right_sheet.stl b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_right_sheet.stl
new file mode 100644
index 0000000..a1fc36e
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/left_knee_to_ankle_right_sheet.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_roll_to_pitch.part b/playground/open_duck_mini_v2/urdfs/assets/left_roll_to_pitch.part
new file mode 100644
index 0000000..d084ffc
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/left_roll_to_pitch.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "Mg7gXWiWLFdTkX/WZ",
+ "isStandardContent": false,
+ "name": "left_roll_to_pitch <1>",
+ "partId": "RRFD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/left_roll_to_pitch.stl b/playground/open_duck_mini_v2/urdfs/assets/left_roll_to_pitch.stl
new file mode 100644
index 0000000..11ee400
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/left_roll_to_pitch.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/leg_spacer.part b/playground/open_duck_mini_v2/urdfs/assets/leg_spacer.part
new file mode 100644
index 0000000..5712510
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/leg_spacer.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "M1AJs3nTP2bD6DgAF",
+ "isStandardContent": false,
+ "name": "leg_spacer <1>",
+ "partId": "RfED",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/leg_spacer.stl b/playground/open_duck_mini_v2/urdfs/assets/leg_spacer.stl
new file mode 100644
index 0000000..336c0b3
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/leg_spacer.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/neck_left_sheet.part b/playground/open_duck_mini_v2/urdfs/assets/neck_left_sheet.part
new file mode 100644
index 0000000..9004962
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/neck_left_sheet.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "M8Je0JZqWOimCS7cY",
+ "isStandardContent": false,
+ "name": "neck_left_sheet <1>",
+ "partId": "RgLD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/neck_left_sheet.stl b/playground/open_duck_mini_v2/urdfs/assets/neck_left_sheet.stl
new file mode 100644
index 0000000..04825be
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/neck_left_sheet.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/neck_right_sheet.part b/playground/open_duck_mini_v2/urdfs/assets/neck_right_sheet.part
new file mode 100644
index 0000000..e7ed9ed
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/neck_right_sheet.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "M8fJckSPn4u+ct8pO",
+ "isStandardContent": false,
+ "name": "neck_right_sheet <1>",
+ "partId": "RgLH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/neck_right_sheet.stl b/playground/open_duck_mini_v2/urdfs/assets/neck_right_sheet.stl
new file mode 100644
index 0000000..867149e
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/neck_right_sheet.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/passive_palonier.part b/playground/open_duck_mini_v2/urdfs/assets/passive_palonier.part
new file mode 100644
index 0000000..9b01991
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/passive_palonier.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "d386542214948bc90a7bc881",
+ "fullConfiguration": "default",
+ "id": "MtwZA0wRrU1lvONjK",
+ "isStandardContent": false,
+ "name": "passive_palonier <1>",
+ "partId": "JVD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/passive_palonier.stl b/playground/open_duck_mini_v2/urdfs/assets/passive_palonier.stl
new file mode 100644
index 0000000..234dd7e
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/passive_palonier.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/power_switch.part b/playground/open_duck_mini_v2/urdfs/assets/power_switch.part
new file mode 100644
index 0000000..65df91a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/power_switch.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "8bfad62b97860b67f75e3376",
+ "fullConfiguration": "default",
+ "id": "MoxN2/6DvG8o5Khzi",
+ "isStandardContent": false,
+ "name": "power_switch <1>",
+ "partId": "JHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/power_switch.stl b/playground/open_duck_mini_v2/urdfs/assets/power_switch.stl
new file mode 100644
index 0000000..a72c233
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/power_switch.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/raspberrypizerow.part b/playground/open_duck_mini_v2/urdfs/assets/raspberrypizerow.part
new file mode 100644
index 0000000..769abe7
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/raspberrypizerow.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "9f45233997c8070932aec904",
+ "fullConfiguration": "default",
+ "id": "MT4+RWBYZDvB/ifWw",
+ "isStandardContent": false,
+ "name": "RaspberryPiZeroW <1>",
+ "partId": "JFH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/raspberrypizerow.stl b/playground/open_duck_mini_v2/urdfs/assets/raspberrypizerow.stl
new file mode 100644
index 0000000..c47c605
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/raspberrypizerow.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/right_antenna_holder.part b/playground/open_duck_mini_v2/urdfs/assets/right_antenna_holder.part
new file mode 100644
index 0000000..6867a20
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/right_antenna_holder.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "M/p8PGArLA1nrXwe8",
+ "isStandardContent": false,
+ "name": "right_antenna_holder <1>",
+ "partId": "RcOD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/right_antenna_holder.stl b/playground/open_duck_mini_v2/urdfs/assets/right_antenna_holder.stl
new file mode 100644
index 0000000..3bf85d6
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/right_antenna_holder.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/right_cache.part b/playground/open_duck_mini_v2/urdfs/assets/right_cache.part
new file mode 100644
index 0000000..e6893ff
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/right_cache.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MBtFsLan/52XkruX7",
+ "isStandardContent": false,
+ "name": "right_cache <1>",
+ "partId": "RfPH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/right_cache.stl b/playground/open_duck_mini_v2/urdfs/assets/right_cache.stl
new file mode 100644
index 0000000..fa40ec6
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/right_cache.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/right_roll_to_pitch.part b/playground/open_duck_mini_v2/urdfs/assets/right_roll_to_pitch.part
new file mode 100644
index 0000000..aa4c05c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/right_roll_to_pitch.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "Mvz4SlAytL1YUO5L4",
+ "isStandardContent": false,
+ "name": "right_roll_to_pitch <1>",
+ "partId": "RfPD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/right_roll_to_pitch.stl b/playground/open_duck_mini_v2/urdfs/assets/right_roll_to_pitch.stl
new file mode 100644
index 0000000..38dd671
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/right_roll_to_pitch.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/roll_bearing.part b/playground/open_duck_mini_v2/urdfs/assets/roll_bearing.part
new file mode 100644
index 0000000..770e3ec
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/roll_bearing.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "Ma27pDNdkzSRCakAZ",
+ "isStandardContent": false,
+ "name": "roll_bearing <1>",
+ "partId": "RtHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/roll_bearing.stl b/playground/open_duck_mini_v2/urdfs/assets/roll_bearing.stl
new file mode 100644
index 0000000..3210d4e
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/roll_bearing.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/roll_motor_bottom.part b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_bottom.part
new file mode 100644
index 0000000..65b6be1
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_bottom.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MjsDdlagt/LopvMjR",
+ "isStandardContent": false,
+ "name": "roll_motor_bottom <1>",
+ "partId": "RGHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/roll_motor_bottom.stl b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_bottom.stl
new file mode 100644
index 0000000..a36dff5
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_bottom.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/roll_motor_top.part b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_top.part
new file mode 100644
index 0000000..d42766e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_top.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MoZYOvTkbbGLGW0df",
+ "isStandardContent": false,
+ "name": "roll_motor_top <1>",
+ "partId": "RyHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/roll_motor_top.stl b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_top.stl
new file mode 100644
index 0000000..99f314c
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/roll_motor_top.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/sg90.part b/playground/open_duck_mini_v2/urdfs/assets/sg90.part
new file mode 100644
index 0000000..c02443b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/sg90.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "349d7eaab34e22a2c029ddc9",
+ "fullConfiguration": "default",
+ "id": "MkrkdH7oZvjAepXlL",
+ "isStandardContent": false,
+ "name": "sg90 <1>",
+ "partId": "JHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/sg90.stl b/playground/open_duck_mini_v2/urdfs/assets/sg90.stl
new file mode 100644
index 0000000..bac6639
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/sg90.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/trunk_bottom.part b/playground/open_duck_mini_v2/urdfs/assets/trunk_bottom.part
new file mode 100644
index 0000000..55deea0
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/trunk_bottom.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MMYHrJ4hqH24cpa8I",
+ "isStandardContent": false,
+ "name": "trunk_bottom <1>",
+ "partId": "RvJH",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/trunk_bottom.stl b/playground/open_duck_mini_v2/urdfs/assets/trunk_bottom.stl
new file mode 100644
index 0000000..48afbc7
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/trunk_bottom.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/trunk_top.part b/playground/open_duck_mini_v2/urdfs/assets/trunk_top.part
new file mode 100644
index 0000000..825a9f6
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/trunk_top.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "560456e30aa4a28c1f2fba59",
+ "fullConfiguration": "default",
+ "id": "MNg8avQSkDpa0UkRX",
+ "isStandardContent": false,
+ "name": "trunk_top <1>",
+ "partId": "RvJD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/trunk_top.stl b/playground/open_duck_mini_v2/urdfs/assets/trunk_top.stl
new file mode 100644
index 0000000..760665c
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/trunk_top.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/usb_c_charger.part b/playground/open_duck_mini_v2/urdfs/assets/usb_c_charger.part
new file mode 100644
index 0000000..8cb8bd9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/usb_c_charger.part
@@ -0,0 +1,14 @@
+{
+ "configuration": "default",
+ "documentId": "a18ff8cc622a533762a3a6f5",
+ "documentMicroversion": "f5e1d9417006aed4e8eece17",
+ "documentVersion": "94881018f8994675184c1f42",
+ "elementId": "1a4a827101fb7d1d1b3cc8de",
+ "fullConfiguration": "default",
+ "id": "MXjBB69uv3FCgauqS",
+ "isStandardContent": false,
+ "name": "usb_c_charger <1>",
+ "partId": "JHD",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/usb_c_charger.stl b/playground/open_duck_mini_v2/urdfs/assets/usb_c_charger.stl
new file mode 100644
index 0000000..2760f99
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/usb_c_charger.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0122topcabinetcase_95.part b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0122topcabinetcase_95.part
new file mode 100644
index 0000000..ff6193a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0122topcabinetcase_95.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "d386542214948bc90a7bc881",
+ "fullConfiguration": "default",
+ "id": "MOFyAb/RZuW0kTpzn",
+ "isStandardContent": false,
+ "name": "WJ-WK00-0122TOPCABINETCASE_95 <1>",
+ "partId": "JFb",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0122topcabinetcase_95.stl b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0122topcabinetcase_95.stl
new file mode 100644
index 0000000..984d136
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0122topcabinetcase_95.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0123middlecase_56.part b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0123middlecase_56.part
new file mode 100644
index 0000000..1d26a22
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0123middlecase_56.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "d386542214948bc90a7bc881",
+ "fullConfiguration": "default",
+ "id": "M1HwhnHIG/iEEwnW3",
+ "isStandardContent": false,
+ "name": "WJ-WK00-0123MIDDLECASE_56 <1>",
+ "partId": "JFP",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0123middlecase_56.stl b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0123middlecase_56.stl
new file mode 100644
index 0000000..098c62c
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0123middlecase_56.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0124bottomcase_45.part b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0124bottomcase_45.part
new file mode 100644
index 0000000..8274cea
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0124bottomcase_45.part
@@ -0,0 +1,13 @@
+{
+ "configuration": "default",
+ "documentId": "64074dfcfa379b37d8a47762",
+ "documentMicroversion": "f0f96f55301e47eaff54f4b3",
+ "elementId": "d386542214948bc90a7bc881",
+ "fullConfiguration": "default",
+ "id": "MOFR6bFTIen7rmARW",
+ "isStandardContent": false,
+ "name": "WJ-WK00-0124BOTTOMCASE_45 <1>",
+ "partId": "JFT",
+ "suppressed": false,
+ "type": "Part"
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0124bottomcase_45.stl b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0124bottomcase_45.stl
new file mode 100644
index 0000000..b5c7064
Binary files /dev/null and b/playground/open_duck_mini_v2/urdfs/assets/wj-wk00-0124bottomcase_45.stl differ
diff --git a/playground/open_duck_mini_v2/urdfs/auto_gait.json b/playground/open_duck_mini_v2/urdfs/auto_gait.json
new file mode 100644
index 0000000..36c1c45
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/auto_gait.json
@@ -0,0 +1,16 @@
+{
+ "slow": 0.05,
+ "medium": 0.1,
+ "fast": 0.15,
+ "dx_max": [0, 0.05],
+ "dy_max": [0, 0.05],
+ "dtheta_max": [0, 0.25],
+ "min_sweep_x": -0.04,
+ "max_sweep_x": 0.06,
+ "min_sweep_y": -0.03,
+ "max_sweep_y": 0.03,
+ "min_sweep_theta": -0.3,
+ "max_sweep_theta": 0.3,
+ "sweep_xy_granularity": 0.02,
+ "sweep_theta_granularity": 0.07
+}
diff --git a/playground/open_duck_mini_v2/urdfs/open_duck_mini_v2.urdf b/playground/open_duck_mini_v2/urdfs/open_duck_mini_v2.urdf
new file mode 100644
index 0000000..72545c7
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/open_duck_mini_v2.urdf
@@ -0,0 +1,522 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_defaults.json b/playground/open_duck_mini_v2/urdfs/placo_defaults.json
new file mode 100644
index 0000000..3378cab
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_defaults.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.1,
+ "dy": 0.0,
+ "dtheta": 0.0,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.18,
+ "startend_double_support_ratio": 1.5,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.2,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -3,
+ "walk_foot_rise_ratio": 0.2,
+ "single_support_duration": 0.17,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": 0.0,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "head_pitch": 0,
+ "head_yaw": 0,
+ "neck_pitch": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/fast.json b/playground/open_duck_mini_v2/urdfs/placo_presets/fast.json
new file mode 100644
index 0000000..6a985b6
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/fast.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.0,
+ "dtheta": 0.0,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.21,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": 5,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 0,
+ "head_pitch": 0,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/medium.json
new file mode 100644
index 0000000..c734273
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.0,
+ "dtheta": 0.0,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/0_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/0_medium.json
new file mode 100644
index 0000000..61f8493
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/0_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/100_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/100_medium.json
new file mode 100644
index 0000000..a95040e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/100_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/101_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/101_medium.json
new file mode 100644
index 0000000..e8f9a70
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/101_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/102_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/102_medium.json
new file mode 100644
index 0000000..a1526f8
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/102_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/103_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/103_medium.json
new file mode 100644
index 0000000..0401e0d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/103_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/104_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/104_medium.json
new file mode 100644
index 0000000..070ae48
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/104_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/105_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/105_medium.json
new file mode 100644
index 0000000..cd2d30d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/105_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/106_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/106_medium.json
new file mode 100644
index 0000000..24e757b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/106_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/107_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/107_medium.json
new file mode 100644
index 0000000..bddf017
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/107_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/108_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/108_medium.json
new file mode 100644
index 0000000..236970e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/108_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/109_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/109_medium.json
new file mode 100644
index 0000000..0032d5e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/109_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/10_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/10_medium.json
new file mode 100644
index 0000000..1e0eeef
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/10_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/110_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/110_medium.json
new file mode 100644
index 0000000..8a66ef9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/110_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/111_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/111_medium.json
new file mode 100644
index 0000000..85d7188
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/111_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/112_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/112_medium.json
new file mode 100644
index 0000000..9e718ca
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/112_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/113_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/113_medium.json
new file mode 100644
index 0000000..3ab6973
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/113_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/114_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/114_medium.json
new file mode 100644
index 0000000..f501927
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/114_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/115_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/115_medium.json
new file mode 100644
index 0000000..d716387
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/115_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/116_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/116_medium.json
new file mode 100644
index 0000000..4faa853
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/116_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/117_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/117_medium.json
new file mode 100644
index 0000000..a6d1ffb
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/117_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/118_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/118_medium.json
new file mode 100644
index 0000000..920b154
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/118_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/119_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/119_medium.json
new file mode 100644
index 0000000..f70d018
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/119_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/11_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/11_medium.json
new file mode 100644
index 0000000..f8d9054
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/11_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/120_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/120_medium.json
new file mode 100644
index 0000000..d99418d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/120_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/121_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/121_medium.json
new file mode 100644
index 0000000..d2d0778
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/121_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/122_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/122_medium.json
new file mode 100644
index 0000000..c634910
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/122_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/123_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/123_medium.json
new file mode 100644
index 0000000..b7a40ce
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/123_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/124_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/124_medium.json
new file mode 100644
index 0000000..4336f51
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/124_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/125_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/125_medium.json
new file mode 100644
index 0000000..2c20d67
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/125_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/126_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/126_medium.json
new file mode 100644
index 0000000..158b844
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/126_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/127_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/127_medium.json
new file mode 100644
index 0000000..408f3c8
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/127_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/128_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/128_medium.json
new file mode 100644
index 0000000..7df721b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/128_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/129_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/129_medium.json
new file mode 100644
index 0000000..59ba8df
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/129_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/12_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/12_medium.json
new file mode 100644
index 0000000..221e21b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/12_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/130_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/130_medium.json
new file mode 100644
index 0000000..3148fc8
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/130_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/131_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/131_medium.json
new file mode 100644
index 0000000..4019f0c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/131_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/132_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/132_medium.json
new file mode 100644
index 0000000..8957fc2
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/132_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/133_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/133_medium.json
new file mode 100644
index 0000000..a33628a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/133_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/134_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/134_medium.json
new file mode 100644
index 0000000..9036d7a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/134_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/135_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/135_medium.json
new file mode 100644
index 0000000..07f87f9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/135_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/136_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/136_medium.json
new file mode 100644
index 0000000..a27b201
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/136_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/137_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/137_medium.json
new file mode 100644
index 0000000..29e85d0
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/137_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/138_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/138_medium.json
new file mode 100644
index 0000000..3beb22a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/138_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/139_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/139_medium.json
new file mode 100644
index 0000000..73aea5a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/139_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/13_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/13_medium.json
new file mode 100644
index 0000000..21813ae
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/13_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/140_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/140_medium.json
new file mode 100644
index 0000000..5973624
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/140_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/141_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/141_medium.json
new file mode 100644
index 0000000..42fe887
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/141_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/142_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/142_medium.json
new file mode 100644
index 0000000..fd69817
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/142_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/143_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/143_medium.json
new file mode 100644
index 0000000..0ccf4bf
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/143_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": 0.05,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/144_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/144_medium.json
new file mode 100644
index 0000000..f9d313d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/144_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/145_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/145_medium.json
new file mode 100644
index 0000000..4c79853
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/145_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/146_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/146_medium.json
new file mode 100644
index 0000000..123f6fc
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/146_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/147_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/147_medium.json
new file mode 100644
index 0000000..9053923
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/147_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/148_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/148_medium.json
new file mode 100644
index 0000000..d9852eb
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/148_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/149_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/149_medium.json
new file mode 100644
index 0000000..cd7f44a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/149_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/14_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/14_medium.json
new file mode 100644
index 0000000..394376f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/14_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/150_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/150_medium.json
new file mode 100644
index 0000000..4608f1e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/150_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/151_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/151_medium.json
new file mode 100644
index 0000000..8fdd937
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/151_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/152_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/152_medium.json
new file mode 100644
index 0000000..7c5a231
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/152_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/153_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/153_medium.json
new file mode 100644
index 0000000..00ec218
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/153_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/154_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/154_medium.json
new file mode 100644
index 0000000..9ff357a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/154_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/155_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/155_medium.json
new file mode 100644
index 0000000..829a4ec
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/155_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/156_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/156_medium.json
new file mode 100644
index 0000000..c990139
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/156_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/157_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/157_medium.json
new file mode 100644
index 0000000..458cd7e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/157_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/158_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/158_medium.json
new file mode 100644
index 0000000..a0f51b3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/158_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/159_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/159_medium.json
new file mode 100644
index 0000000..c783217
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/159_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/15_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/15_medium.json
new file mode 100644
index 0000000..8890726
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/15_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/160_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/160_medium.json
new file mode 100644
index 0000000..9810cb7
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/160_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/161_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/161_medium.json
new file mode 100644
index 0000000..41eda98
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/161_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/162_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/162_medium.json
new file mode 100644
index 0000000..65650f3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/162_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/163_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/163_medium.json
new file mode 100644
index 0000000..341573a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/163_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/164_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/164_medium.json
new file mode 100644
index 0000000..cd9eaa4
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/164_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/165_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/165_medium.json
new file mode 100644
index 0000000..307f8ad
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/165_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/166_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/166_medium.json
new file mode 100644
index 0000000..1b5c8f5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/166_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/167_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/167_medium.json
new file mode 100644
index 0000000..2aaa184
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/167_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": 0.12,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/168_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/168_medium.json
new file mode 100644
index 0000000..ea92d93
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/168_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/169_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/169_medium.json
new file mode 100644
index 0000000..4a2171a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/169_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/16_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/16_medium.json
new file mode 100644
index 0000000..44aa300
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/16_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/170_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/170_medium.json
new file mode 100644
index 0000000..640079e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/170_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/171_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/171_medium.json
new file mode 100644
index 0000000..278475f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/171_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/172_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/172_medium.json
new file mode 100644
index 0000000..13d6da8
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/172_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/173_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/173_medium.json
new file mode 100644
index 0000000..31a2c00
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/173_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/174_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/174_medium.json
new file mode 100644
index 0000000..ee1aa88
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/174_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/175_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/175_medium.json
new file mode 100644
index 0000000..6d8d043
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/175_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/176_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/176_medium.json
new file mode 100644
index 0000000..96a61b0
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/176_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/177_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/177_medium.json
new file mode 100644
index 0000000..daf097b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/177_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/178_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/178_medium.json
new file mode 100644
index 0000000..9fd0798
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/178_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/179_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/179_medium.json
new file mode 100644
index 0000000..260eac9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/179_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/17_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/17_medium.json
new file mode 100644
index 0000000..312d4bb
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/17_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/180_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/180_medium.json
new file mode 100644
index 0000000..be81485
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/180_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/181_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/181_medium.json
new file mode 100644
index 0000000..0fc8aef
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/181_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/182_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/182_medium.json
new file mode 100644
index 0000000..13650fc
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/182_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/183_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/183_medium.json
new file mode 100644
index 0000000..bb41829
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/183_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/184_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/184_medium.json
new file mode 100644
index 0000000..24e54c0
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/184_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/185_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/185_medium.json
new file mode 100644
index 0000000..1c88ffd
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/185_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/186_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/186_medium.json
new file mode 100644
index 0000000..4ef3d9c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/186_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/187_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/187_medium.json
new file mode 100644
index 0000000..e8c53e6
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/187_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/188_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/188_medium.json
new file mode 100644
index 0000000..dd62569
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/188_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/189_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/189_medium.json
new file mode 100644
index 0000000..4c17784
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/189_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/18_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/18_medium.json
new file mode 100644
index 0000000..0c1eaf0
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/18_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/190_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/190_medium.json
new file mode 100644
index 0000000..61ddd04
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/190_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/191_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/191_medium.json
new file mode 100644
index 0000000..0257d35
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/191_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": 0.19,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/192_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/192_medium.json
new file mode 100644
index 0000000..869a32a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/192_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/193_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/193_medium.json
new file mode 100644
index 0000000..204292d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/193_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/194_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/194_medium.json
new file mode 100644
index 0000000..84dfeec
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/194_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/195_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/195_medium.json
new file mode 100644
index 0000000..fe29312
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/195_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/196_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/196_medium.json
new file mode 100644
index 0000000..e633f4f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/196_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/197_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/197_medium.json
new file mode 100644
index 0000000..b5f5108
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/197_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/198_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/198_medium.json
new file mode 100644
index 0000000..fb89945
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/198_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/199_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/199_medium.json
new file mode 100644
index 0000000..094eacb
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/199_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/19_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/19_medium.json
new file mode 100644
index 0000000..d562523
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/19_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/1_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/1_medium.json
new file mode 100644
index 0000000..2cb43b4
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/1_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/200_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/200_medium.json
new file mode 100644
index 0000000..42c7286
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/200_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/201_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/201_medium.json
new file mode 100644
index 0000000..36c6511
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/201_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/202_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/202_medium.json
new file mode 100644
index 0000000..fe4694a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/202_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/203_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/203_medium.json
new file mode 100644
index 0000000..4acdc0c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/203_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/204_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/204_medium.json
new file mode 100644
index 0000000..26bae2c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/204_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/205_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/205_medium.json
new file mode 100644
index 0000000..9b59227
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/205_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/206_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/206_medium.json
new file mode 100644
index 0000000..ef53862
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/206_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/207_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/207_medium.json
new file mode 100644
index 0000000..7829709
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/207_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/208_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/208_medium.json
new file mode 100644
index 0000000..2a75466
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/208_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/209_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/209_medium.json
new file mode 100644
index 0000000..e953a21
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/209_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/20_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/20_medium.json
new file mode 100644
index 0000000..9502fbf
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/20_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/210_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/210_medium.json
new file mode 100644
index 0000000..077543c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/210_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/211_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/211_medium.json
new file mode 100644
index 0000000..c546333
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/211_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/212_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/212_medium.json
new file mode 100644
index 0000000..db62060
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/212_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/213_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/213_medium.json
new file mode 100644
index 0000000..82b3e7d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/213_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/214_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/214_medium.json
new file mode 100644
index 0000000..a96e4f9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/214_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/215_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/215_medium.json
new file mode 100644
index 0000000..bc64a24
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/215_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": 0.26,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/216_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/216_medium.json
new file mode 100644
index 0000000..ed4cfee
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/216_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/217_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/217_medium.json
new file mode 100644
index 0000000..f7fc839
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/217_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/218_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/218_medium.json
new file mode 100644
index 0000000..a702d7c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/218_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/219_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/219_medium.json
new file mode 100644
index 0000000..06179d3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/219_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/21_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/21_medium.json
new file mode 100644
index 0000000..400bfad
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/21_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/220_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/220_medium.json
new file mode 100644
index 0000000..1ea2a52
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/220_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/221_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/221_medium.json
new file mode 100644
index 0000000..86a61a3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/221_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/222_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/222_medium.json
new file mode 100644
index 0000000..8e476c9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/222_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/223_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/223_medium.json
new file mode 100644
index 0000000..904d623
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/223_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/224_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/224_medium.json
new file mode 100644
index 0000000..86c7ef6
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/224_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/225_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/225_medium.json
new file mode 100644
index 0000000..97da5da
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/225_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/226_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/226_medium.json
new file mode 100644
index 0000000..5bd82c1
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/226_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/227_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/227_medium.json
new file mode 100644
index 0000000..e9a13fa
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/227_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/228_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/228_medium.json
new file mode 100644
index 0000000..d94242a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/228_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/229_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/229_medium.json
new file mode 100644
index 0000000..2e14798
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/229_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/22_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/22_medium.json
new file mode 100644
index 0000000..f19a07d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/22_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/230_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/230_medium.json
new file mode 100644
index 0000000..b54f2f3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/230_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/231_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/231_medium.json
new file mode 100644
index 0000000..18b4315
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/231_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/232_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/232_medium.json
new file mode 100644
index 0000000..f6cd526
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/232_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/233_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/233_medium.json
new file mode 100644
index 0000000..cac20f3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/233_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/234_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/234_medium.json
new file mode 100644
index 0000000..59a9a78
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/234_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/235_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/235_medium.json
new file mode 100644
index 0000000..9a9d355
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/235_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/236_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/236_medium.json
new file mode 100644
index 0000000..51b99f5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/236_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/237_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/237_medium.json
new file mode 100644
index 0000000..0dd6633
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/237_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/238_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/238_medium.json
new file mode 100644
index 0000000..7df191d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/238_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/239_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/239_medium.json
new file mode 100644
index 0000000..2e5e752
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/239_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": 0.33,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/23_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/23_medium.json
new file mode 100644
index 0000000..39c2ce9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/23_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/24_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/24_medium.json
new file mode 100644
index 0000000..e73b441
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/24_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/25_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/25_medium.json
new file mode 100644
index 0000000..c199b36
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/25_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/26_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/26_medium.json
new file mode 100644
index 0000000..ab10c89
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/26_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/27_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/27_medium.json
new file mode 100644
index 0000000..d3ea826
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/27_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/28_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/28_medium.json
new file mode 100644
index 0000000..4171638
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/28_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/29_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/29_medium.json
new file mode 100644
index 0000000..89e486b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/29_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/2_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/2_medium.json
new file mode 100644
index 0000000..dd8caba
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/2_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/30_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/30_medium.json
new file mode 100644
index 0000000..05fa0ad
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/30_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/31_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/31_medium.json
new file mode 100644
index 0000000..cec6c54
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/31_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/32_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/32_medium.json
new file mode 100644
index 0000000..9333406
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/32_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/33_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/33_medium.json
new file mode 100644
index 0000000..7f44e95
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/33_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/34_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/34_medium.json
new file mode 100644
index 0000000..e21df5d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/34_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/35_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/35_medium.json
new file mode 100644
index 0000000..41f08a5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/35_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/36_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/36_medium.json
new file mode 100644
index 0000000..0b755e1
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/36_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/37_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/37_medium.json
new file mode 100644
index 0000000..eb0987f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/37_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/38_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/38_medium.json
new file mode 100644
index 0000000..0d30d2a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/38_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/39_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/39_medium.json
new file mode 100644
index 0000000..a0707b8
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/39_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/3_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/3_medium.json
new file mode 100644
index 0000000..f225813
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/3_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/40_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/40_medium.json
new file mode 100644
index 0000000..cec4952
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/40_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/41_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/41_medium.json
new file mode 100644
index 0000000..20d30b8
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/41_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/42_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/42_medium.json
new file mode 100644
index 0000000..03b6d85
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/42_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/43_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/43_medium.json
new file mode 100644
index 0000000..6194ff2
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/43_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/44_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/44_medium.json
new file mode 100644
index 0000000..5564d02
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/44_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/45_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/45_medium.json
new file mode 100644
index 0000000..fa90d2e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/45_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/46_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/46_medium.json
new file mode 100644
index 0000000..e4218a3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/46_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/47_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/47_medium.json
new file mode 100644
index 0000000..9a39f3d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/47_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": -0.23,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/48_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/48_medium.json
new file mode 100644
index 0000000..b20c636
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/48_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/49_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/49_medium.json
new file mode 100644
index 0000000..bb33e71
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/49_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/4_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/4_medium.json
new file mode 100644
index 0000000..382f607
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/4_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/50_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/50_medium.json
new file mode 100644
index 0000000..c84f7c1
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/50_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/51_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/51_medium.json
new file mode 100644
index 0000000..c5e7010
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/51_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/52_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/52_medium.json
new file mode 100644
index 0000000..55d6243
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/52_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/53_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/53_medium.json
new file mode 100644
index 0000000..7210d52
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/53_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/54_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/54_medium.json
new file mode 100644
index 0000000..169589d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/54_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/55_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/55_medium.json
new file mode 100644
index 0000000..cb1ae10
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/55_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/56_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/56_medium.json
new file mode 100644
index 0000000..571d419
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/56_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/57_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/57_medium.json
new file mode 100644
index 0000000..f5a036d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/57_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/58_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/58_medium.json
new file mode 100644
index 0000000..c9c07a5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/58_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/59_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/59_medium.json
new file mode 100644
index 0000000..ec0f7b9
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/59_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/5_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/5_medium.json
new file mode 100644
index 0000000..83e2df7
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/5_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/60_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/60_medium.json
new file mode 100644
index 0000000..90d68a3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/60_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/61_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/61_medium.json
new file mode 100644
index 0000000..873ce8e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/61_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/62_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/62_medium.json
new file mode 100644
index 0000000..b151931
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/62_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/63_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/63_medium.json
new file mode 100644
index 0000000..936fb79
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/63_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/64_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/64_medium.json
new file mode 100644
index 0000000..cb589d1
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/64_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/65_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/65_medium.json
new file mode 100644
index 0000000..f9d6e76
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/65_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/66_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/66_medium.json
new file mode 100644
index 0000000..72de659
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/66_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/67_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/67_medium.json
new file mode 100644
index 0000000..54fb7e5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/67_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/68_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/68_medium.json
new file mode 100644
index 0000000..a762c21
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/68_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/69_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/69_medium.json
new file mode 100644
index 0000000..27e7da0
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/69_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/6_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/6_medium.json
new file mode 100644
index 0000000..87a4511
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/6_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/70_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/70_medium.json
new file mode 100644
index 0000000..bb8b494
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/70_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/71_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/71_medium.json
new file mode 100644
index 0000000..5075a09
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/71_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": -0.16,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/72_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/72_medium.json
new file mode 100644
index 0000000..d2bc99b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/72_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/73_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/73_medium.json
new file mode 100644
index 0000000..11c7b23
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/73_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/74_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/74_medium.json
new file mode 100644
index 0000000..f4c806f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/74_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/75_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/75_medium.json
new file mode 100644
index 0000000..b7634df
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/75_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/76_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/76_medium.json
new file mode 100644
index 0000000..3068e7d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/76_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/77_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/77_medium.json
new file mode 100644
index 0000000..b46867d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/77_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/78_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/78_medium.json
new file mode 100644
index 0000000..dfd802e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/78_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/79_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/79_medium.json
new file mode 100644
index 0000000..e50cc7c
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/79_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/7_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/7_medium.json
new file mode 100644
index 0000000..955a46f
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/7_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/80_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/80_medium.json
new file mode 100644
index 0000000..51d3f57
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/80_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/81_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/81_medium.json
new file mode 100644
index 0000000..c97b3bb
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/81_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/82_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/82_medium.json
new file mode 100644
index 0000000..979ec3b
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/82_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": -0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/83_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/83_medium.json
new file mode 100644
index 0000000..d5995a6
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/83_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": -0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/84_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/84_medium.json
new file mode 100644
index 0000000..40c9a5d
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/84_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/85_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/85_medium.json
new file mode 100644
index 0000000..eaad247
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/85_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/86_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/86_medium.json
new file mode 100644
index 0000000..4a8bd11
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/86_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/87_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/87_medium.json
new file mode 100644
index 0000000..7452960
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/87_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/88_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/88_medium.json
new file mode 100644
index 0000000..1e2a325
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/88_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/89_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/89_medium.json
new file mode 100644
index 0000000..56d0081
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/89_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.01,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/8_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/8_medium.json
new file mode 100644
index 0000000..5d096f5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/8_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/90_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/90_medium.json
new file mode 100644
index 0000000..10ec706
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/90_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": 0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/91_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/91_medium.json
new file mode 100644
index 0000000..3af70d7
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/91_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": 0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/92_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/92_medium.json
new file mode 100644
index 0000000..bf1a7c5
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/92_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": 0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/93_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/93_medium.json
new file mode 100644
index 0000000..75986c3
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/93_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": 0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/94_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/94_medium.json
new file mode 100644
index 0000000..88cc380
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/94_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.04,
+ "dy": 0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/95_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/95_medium.json
new file mode 100644
index 0000000..022a4d8
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/95_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.06,
+ "dy": 0.03,
+ "dtheta": -0.09,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/96_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/96_medium.json
new file mode 100644
index 0000000..5112db6
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/96_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.04,
+ "dy": -0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/97_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/97_medium.json
new file mode 100644
index 0000000..e0bed45
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/97_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": -0.02,
+ "dy": -0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/98_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/98_medium.json
new file mode 100644
index 0000000..658f529
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/98_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.0,
+ "dy": -0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/99_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/99_medium.json
new file mode 100644
index 0000000..a8cc36e
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/99_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.03,
+ "dtheta": -0.02,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/9_medium.json b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/9_medium.json
new file mode 100644
index 0000000..960d86a
--- /dev/null
+++ b/playground/open_duck_mini_v2/urdfs/placo_presets/tmp/9_medium.json
@@ -0,0 +1,52 @@
+{
+ "dx": 0.02,
+ "dy": -0.01,
+ "dtheta": -0.3,
+ "duration": 8,
+ "hardware": true,
+ "double_support_ratio": 0.5,
+ "startend_double_support_ratio": 1.0,
+ "planned_timesteps": 48,
+ "replan_timesteps": 10,
+ "walk_com_height": 0.205,
+ "walk_foot_height": 0.04,
+ "walk_trunk_pitch": -4,
+ "walk_foot_rise_ratio": 0.02,
+ "single_support_duration": 0.18,
+ "single_support_timesteps": 10,
+ "foot_length": 0.06,
+ "feet_spacing": 0.16,
+ "zmp_margin": 0.0,
+ "foot_zmp_target_x": 0.0,
+ "foot_zmp_target_y": -0.03,
+ "walk_max_dtheta": 1.0,
+ "walk_max_dy": 0.1,
+ "walk_max_dx_forward": 0.08,
+ "walk_max_dx_backward": 0.03,
+ "joints": [
+ "left_hip_yaw",
+ "left_hip_roll",
+ "left_hip_pitch",
+ "left_knee",
+ "left_ankle",
+ "neck_pitch",
+ "head_pitch",
+ "head_yaw",
+ "head_roll",
+ "left_antenna",
+ "right_antenna",
+ "right_hip_yaw",
+ "right_hip_roll",
+ "right_hip_pitch",
+ "right_knee",
+ "right_ankle"
+ ],
+ "joint_angles": {
+ "neck_pitch": 20,
+ "head_pitch": -26,
+ "head_yaw": 0,
+ "head_roll": 0,
+ "left_antenna": 0,
+ "right_antenna": 0
+ }
+}
\ No newline at end of file
diff --git a/playground/open_duck_mini_v2/xmls/open_duck_mini_v2.xml b/playground/open_duck_mini_v2/xmls/open_duck_mini_v2.xml
index 86204bf..5799310 100644
--- a/playground/open_duck_mini_v2/xmls/open_duck_mini_v2.xml
+++ b/playground/open_duck_mini_v2/xmls/open_duck_mini_v2.xml
@@ -57,7 +57,9 @@
-
+
+
+
-
+
+
+