update the trainning of g1,h1,h1_2
This commit is contained in:
parent
6ce61a0241
commit
bd00c6a2a1
@ -2,13 +2,16 @@ from legged_gym import LEGGED_GYM_ROOT_DIR, LEGGED_GYM_ENVS_DIR
|
|||||||
|
|
||||||
from legged_gym.envs.go2.go2_config import GO2RoughCfg, GO2RoughCfgPPO
|
from legged_gym.envs.go2.go2_config import GO2RoughCfg, GO2RoughCfgPPO
|
||||||
from legged_gym.envs.h1.h1_config import H1RoughCfg, H1RoughCfgPPO
|
from legged_gym.envs.h1.h1_config import H1RoughCfg, H1RoughCfgPPO
|
||||||
|
from legged_gym.envs.h1.h1_env import H1Robot
|
||||||
from legged_gym.envs.h1_2.h1_2_config import H1_2RoughCfg, H1_2RoughCfgPPO
|
from legged_gym.envs.h1_2.h1_2_config import H1_2RoughCfg, H1_2RoughCfgPPO
|
||||||
|
from legged_gym.envs.h1_2.h1_2_env import H1_2Robot
|
||||||
from legged_gym.envs.g1.g1_config import G1RoughCfg, G1RoughCfgPPO
|
from legged_gym.envs.g1.g1_config import G1RoughCfg, G1RoughCfgPPO
|
||||||
|
from legged_gym.envs.g1.g1_env import G1Robot
|
||||||
from .base.legged_robot import LeggedRobot
|
from .base.legged_robot import LeggedRobot
|
||||||
|
|
||||||
from legged_gym.utils.task_registry import task_registry
|
from legged_gym.utils.task_registry import task_registry
|
||||||
|
|
||||||
task_registry.register( "go2", LeggedRobot, GO2RoughCfg(), GO2RoughCfgPPO())
|
task_registry.register( "go2", LeggedRobot, GO2RoughCfg(), GO2RoughCfgPPO())
|
||||||
task_registry.register( "h1", LeggedRobot, H1RoughCfg(), H1RoughCfgPPO())
|
task_registry.register( "h1", H1Robot, H1RoughCfg(), H1RoughCfgPPO())
|
||||||
task_registry.register( "h1_2", LeggedRobot, H1_2RoughCfg(), H1_2RoughCfgPPO())
|
task_registry.register( "h1_2", H1_2Robot, H1_2RoughCfg(), H1_2RoughCfgPPO())
|
||||||
task_registry.register( "g1", LeggedRobot, G1RoughCfg(), G1RoughCfgPPO())
|
task_registry.register( "g1", G1Robot, G1RoughCfg(), G1RoughCfgPPO())
|
||||||
|
@ -20,18 +20,29 @@ class G1RoughCfg( LeggedRobotCfg ):
|
|||||||
}
|
}
|
||||||
|
|
||||||
class env(LeggedRobotCfg.env):
|
class env(LeggedRobotCfg.env):
|
||||||
num_observations = 48
|
num_observations = 47
|
||||||
|
num_privileged_obs = 50
|
||||||
num_actions = 12
|
num_actions = 12
|
||||||
|
|
||||||
|
|
||||||
|
class domain_rand(LeggedRobotCfg.domain_rand):
|
||||||
|
randomize_friction = True
|
||||||
|
friction_range = [0.1, 1.25]
|
||||||
|
randomize_base_mass = True
|
||||||
|
added_mass_range = [-1., 3.]
|
||||||
|
push_robots = True
|
||||||
|
push_interval_s = 5
|
||||||
|
max_push_vel_xy = 1.5
|
||||||
|
|
||||||
|
|
||||||
class control( LeggedRobotCfg.control ):
|
class control( LeggedRobotCfg.control ):
|
||||||
# PD Drive parameters:
|
# PD Drive parameters:
|
||||||
control_type = 'P'
|
control_type = 'P'
|
||||||
# PD Drive parameters:
|
# PD Drive parameters:
|
||||||
stiffness = {'hip_yaw': 150,
|
stiffness = {'hip_yaw': 100,
|
||||||
'hip_roll': 150,
|
'hip_roll': 100,
|
||||||
'hip_pitch': 150,
|
'hip_pitch': 100,
|
||||||
'knee': 300,
|
'knee': 150,
|
||||||
'ankle': 40,
|
'ankle': 40,
|
||||||
} # [N*m/rad]
|
} # [N*m/rad]
|
||||||
damping = { 'hip_yaw': 2,
|
damping = { 'hip_yaw': 2,
|
||||||
@ -46,17 +57,18 @@ class G1RoughCfg( LeggedRobotCfg ):
|
|||||||
decimation = 4
|
decimation = 4
|
||||||
|
|
||||||
class asset( LeggedRobotCfg.asset ):
|
class asset( LeggedRobotCfg.asset ):
|
||||||
file = '{LEGGED_GYM_ROOT_DIR}/resources/robots/g1/urdf/g1.urdf'
|
file = '{LEGGED_GYM_ROOT_DIR}/resources/robots/g1_description/g1_12dof.urdf'
|
||||||
name = "g1"
|
name = "g1"
|
||||||
foot_name = "ankle_roll"
|
foot_name = "ankle_roll"
|
||||||
penalize_contacts_on = ["hip", "knee"]
|
penalize_contacts_on = ["hip", "knee"]
|
||||||
terminate_after_contacts_on = ["torso"]
|
terminate_after_contacts_on = ["pelvis"]
|
||||||
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
|
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
|
||||||
flip_visual_attachments = False
|
flip_visual_attachments = False
|
||||||
|
|
||||||
class rewards( LeggedRobotCfg.rewards ):
|
class rewards( LeggedRobotCfg.rewards ):
|
||||||
soft_dof_pos_limit = 0.9
|
soft_dof_pos_limit = 0.9
|
||||||
base_height_target = 0.728
|
base_height_target = 0.78
|
||||||
|
|
||||||
class scales( LeggedRobotCfg.rewards.scales ):
|
class scales( LeggedRobotCfg.rewards.scales ):
|
||||||
tracking_lin_vel = 1.0
|
tracking_lin_vel = 1.0
|
||||||
tracking_ang_vel = 0.5
|
tracking_ang_vel = 0.5
|
||||||
@ -64,19 +76,34 @@ class G1RoughCfg( LeggedRobotCfg ):
|
|||||||
ang_vel_xy = -0.05
|
ang_vel_xy = -0.05
|
||||||
orientation = -1.0
|
orientation = -1.0
|
||||||
base_height = -10.0
|
base_height = -10.0
|
||||||
dof_acc = -2.5e-8
|
dof_acc = -2.5e-7
|
||||||
feet_air_time = 1.0
|
dof_vel = -1e-3
|
||||||
|
feet_air_time = 0.0
|
||||||
collision = 0.0
|
collision = 0.0
|
||||||
action_rate = -0.01
|
action_rate = -0.01
|
||||||
# torques = -0.0001
|
|
||||||
dof_pos_limits = -5.0
|
dof_pos_limits = -5.0
|
||||||
|
alive = 0.15
|
||||||
|
hip_pos = -1.0
|
||||||
|
contact_no_vel = -0.2
|
||||||
|
feet_swing_height = -20.0
|
||||||
|
contact = 0.18
|
||||||
|
|
||||||
class G1RoughCfgPPO( LeggedRobotCfgPPO ):
|
class G1RoughCfgPPO( LeggedRobotCfgPPO ):
|
||||||
class policy:
|
class policy:
|
||||||
init_noise_std = 0.8
|
init_noise_std = 0.8
|
||||||
|
actor_hidden_dims = [32]
|
||||||
|
critic_hidden_dims = [32]
|
||||||
|
activation = 'elu' # can be elu, relu, selu, crelu, lrelu, tanh, sigmoid
|
||||||
|
# only for 'ActorCriticRecurrent':
|
||||||
|
rnn_type = 'lstm'
|
||||||
|
rnn_hidden_size = 64
|
||||||
|
rnn_num_layers = 1
|
||||||
|
|
||||||
class algorithm( LeggedRobotCfgPPO.algorithm ):
|
class algorithm( LeggedRobotCfgPPO.algorithm ):
|
||||||
entropy_coef = 0.01
|
entropy_coef = 0.01
|
||||||
class runner( LeggedRobotCfgPPO.runner ):
|
class runner( LeggedRobotCfgPPO.runner ):
|
||||||
|
policy_class_name = "ActorCriticRecurrent"
|
||||||
|
max_iterations = 10000
|
||||||
run_name = ''
|
run_name = ''
|
||||||
experiment_name = 'g1'
|
experiment_name = 'g1'
|
||||||
|
|
||||||
|
124
legged_gym/envs/g1/g1_env.py
Normal file
124
legged_gym/envs/g1/g1_env.py
Normal file
@ -0,0 +1,124 @@
|
|||||||
|
|
||||||
|
from legged_gym.envs.base.legged_robot import LeggedRobot
|
||||||
|
|
||||||
|
from isaacgym.torch_utils import *
|
||||||
|
from isaacgym import gymtorch, gymapi, gymutil
|
||||||
|
import torch
|
||||||
|
|
||||||
|
class G1Robot(LeggedRobot):
|
||||||
|
|
||||||
|
def _get_noise_scale_vec(self, cfg):
|
||||||
|
""" Sets a vector used to scale the noise added to the observations.
|
||||||
|
[NOTE]: Must be adapted when changing the observations structure
|
||||||
|
|
||||||
|
Args:
|
||||||
|
cfg (Dict): Environment config file
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
[torch.Tensor]: Vector of scales used to multiply a uniform distribution in [-1, 1]
|
||||||
|
"""
|
||||||
|
noise_vec = torch.zeros_like(self.obs_buf[0])
|
||||||
|
self.add_noise = self.cfg.noise.add_noise
|
||||||
|
noise_scales = self.cfg.noise.noise_scales
|
||||||
|
noise_level = self.cfg.noise.noise_level
|
||||||
|
noise_vec[:3] = noise_scales.ang_vel * noise_level * self.obs_scales.ang_vel
|
||||||
|
noise_vec[3:6] = noise_scales.gravity * noise_level
|
||||||
|
noise_vec[6:9] = 0. # commands
|
||||||
|
noise_vec[9:9+self.num_actions] = noise_scales.dof_pos * noise_level * self.obs_scales.dof_pos
|
||||||
|
noise_vec[9+self.num_actions:9+2*self.num_actions] = noise_scales.dof_vel * noise_level * self.obs_scales.dof_vel
|
||||||
|
noise_vec[9+2*self.num_actions:9+3*self.num_actions] = 0. # previous actions
|
||||||
|
noise_vec[9+3*self.num_actions:9+3*self.num_actions+2] = 0. # sin/cos phase
|
||||||
|
|
||||||
|
return noise_vec
|
||||||
|
|
||||||
|
def _init_foot(self):
|
||||||
|
self.feet_num = len(self.feet_indices)
|
||||||
|
|
||||||
|
rigid_body_state = self.gym.acquire_rigid_body_state_tensor(self.sim)
|
||||||
|
self.rigid_body_states = gymtorch.wrap_tensor(rigid_body_state)
|
||||||
|
self.rigid_body_states_view = self.rigid_body_states.view(self.num_envs, -1, 13)
|
||||||
|
self.feet_state = self.rigid_body_states_view[:, self.feet_indices, :]
|
||||||
|
self.feet_pos = self.feet_state[:, :, :3]
|
||||||
|
self.feet_vel = self.feet_state[:, :, 7:10]
|
||||||
|
|
||||||
|
def _init_buffers(self):
|
||||||
|
super()._init_buffers()
|
||||||
|
self._init_foot()
|
||||||
|
|
||||||
|
def update_feet_state(self):
|
||||||
|
self.gym.refresh_rigid_body_state_tensor(self.sim)
|
||||||
|
|
||||||
|
self.feet_state = self.rigid_body_states_view[:, self.feet_indices, :]
|
||||||
|
self.feet_pos = self.feet_state[:, :, :3]
|
||||||
|
self.feet_vel = self.feet_state[:, :, 7:10]
|
||||||
|
|
||||||
|
def _post_physics_step_callback(self):
|
||||||
|
self.update_feet_state()
|
||||||
|
|
||||||
|
period = 0.8
|
||||||
|
offset = 0.5
|
||||||
|
self.phase = (self.episode_length_buf * self.dt) % period / period
|
||||||
|
self.phase_left = self.phase
|
||||||
|
self.phase_right = (self.phase + offset) % 1
|
||||||
|
self.leg_phase = torch.cat([self.phase_left.unsqueeze(1), self.phase_right.unsqueeze(1)], dim=-1)
|
||||||
|
|
||||||
|
return super()._post_physics_step_callback()
|
||||||
|
|
||||||
|
|
||||||
|
def compute_observations(self):
|
||||||
|
""" Computes observations
|
||||||
|
"""
|
||||||
|
sin_phase = torch.sin(2 * np.pi * self.phase ).unsqueeze(1)
|
||||||
|
cos_phase = torch.cos(2 * np.pi * self.phase ).unsqueeze(1)
|
||||||
|
self.obs_buf = torch.cat(( self.base_ang_vel * self.obs_scales.ang_vel,
|
||||||
|
self.projected_gravity,
|
||||||
|
self.commands[:, :3] * self.commands_scale,
|
||||||
|
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
|
||||||
|
self.dof_vel * self.obs_scales.dof_vel,
|
||||||
|
self.actions,
|
||||||
|
sin_phase,
|
||||||
|
cos_phase
|
||||||
|
),dim=-1)
|
||||||
|
self.privileged_obs_buf = torch.cat(( self.base_lin_vel * self.obs_scales.lin_vel,
|
||||||
|
self.base_ang_vel * self.obs_scales.ang_vel,
|
||||||
|
self.projected_gravity,
|
||||||
|
self.commands[:, :3] * self.commands_scale,
|
||||||
|
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
|
||||||
|
self.dof_vel * self.obs_scales.dof_vel,
|
||||||
|
self.actions,
|
||||||
|
sin_phase,
|
||||||
|
cos_phase
|
||||||
|
),dim=-1)
|
||||||
|
# add perceptive inputs if not blind
|
||||||
|
# add noise if needed
|
||||||
|
if self.add_noise:
|
||||||
|
self.obs_buf += (2 * torch.rand_like(self.obs_buf) - 1) * self.noise_scale_vec
|
||||||
|
|
||||||
|
|
||||||
|
def _reward_contact(self):
|
||||||
|
res = torch.zeros(self.num_envs, dtype=torch.float, device=self.device)
|
||||||
|
for i in range(self.feet_num):
|
||||||
|
is_stance = self.leg_phase[:, i] < 0.55
|
||||||
|
contact = self.contact_forces[:, self.feet_indices[i], 2] > 1
|
||||||
|
res += ~(contact ^ is_stance)
|
||||||
|
return res
|
||||||
|
|
||||||
|
def _reward_feet_swing_height(self):
|
||||||
|
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
|
||||||
|
pos_error = torch.square(self.feet_pos[:, :, 2] - 0.08) * ~contact
|
||||||
|
return torch.sum(pos_error, dim=(1))
|
||||||
|
|
||||||
|
def _reward_alive(self):
|
||||||
|
# Reward for staying alive
|
||||||
|
return 1.0
|
||||||
|
|
||||||
|
def _reward_contact_no_vel(self):
|
||||||
|
# Penalize contact with no velocity
|
||||||
|
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
|
||||||
|
contact_feet_vel = self.feet_vel * contact.unsqueeze(-1)
|
||||||
|
penalize = torch.square(contact_feet_vel[:, :, :3])
|
||||||
|
return torch.sum(penalize, dim=(1,2))
|
||||||
|
|
||||||
|
def _reward_hip_pos(self):
|
||||||
|
return torch.sum(torch.square(self.dof_pos[:,[1,2,7,8]]), dim=1)
|
||||||
|
|
@ -6,14 +6,14 @@ class H1RoughCfg( LeggedRobotCfg ):
|
|||||||
default_joint_angles = { # = target angles [rad] when action = 0.0
|
default_joint_angles = { # = target angles [rad] when action = 0.0
|
||||||
'left_hip_yaw_joint' : 0. ,
|
'left_hip_yaw_joint' : 0. ,
|
||||||
'left_hip_roll_joint' : 0,
|
'left_hip_roll_joint' : 0,
|
||||||
'left_hip_pitch_joint' : -0.4,
|
'left_hip_pitch_joint' : -0.1,
|
||||||
'left_knee_joint' : 0.8,
|
'left_knee_joint' : 0.3,
|
||||||
'left_ankle_joint' : -0.4,
|
'left_ankle_joint' : -0.2,
|
||||||
'right_hip_yaw_joint' : 0.,
|
'right_hip_yaw_joint' : 0.,
|
||||||
'right_hip_roll_joint' : 0,
|
'right_hip_roll_joint' : 0,
|
||||||
'right_hip_pitch_joint' : -0.4,
|
'right_hip_pitch_joint' : -0.1,
|
||||||
'right_knee_joint' : 0.8,
|
'right_knee_joint' : 0.3,
|
||||||
'right_ankle_joint' : -0.4,
|
'right_ankle_joint' : -0.2,
|
||||||
'torso_joint' : 0.,
|
'torso_joint' : 0.,
|
||||||
'left_shoulder_pitch_joint' : 0.,
|
'left_shoulder_pitch_joint' : 0.,
|
||||||
'left_shoulder_roll_joint' : 0,
|
'left_shoulder_roll_joint' : 0,
|
||||||
@ -26,27 +26,38 @@ class H1RoughCfg( LeggedRobotCfg ):
|
|||||||
}
|
}
|
||||||
|
|
||||||
class env(LeggedRobotCfg.env):
|
class env(LeggedRobotCfg.env):
|
||||||
num_observations = 42
|
# 3 + 3 + 3 + 10 + 10 + 10 + 2 = 41
|
||||||
|
num_observations = 41
|
||||||
|
num_privileged_obs = 44
|
||||||
num_actions = 10
|
num_actions = 10
|
||||||
|
|
||||||
|
|
||||||
|
class domain_rand(LeggedRobotCfg.domain_rand):
|
||||||
|
randomize_friction = True
|
||||||
|
friction_range = [0.1, 1.25]
|
||||||
|
randomize_base_mass = True
|
||||||
|
added_mass_range = [-1., 3.]
|
||||||
|
push_robots = True
|
||||||
|
push_interval_s = 5
|
||||||
|
max_push_vel_xy = 1.5
|
||||||
|
|
||||||
class control( LeggedRobotCfg.control ):
|
class control( LeggedRobotCfg.control ):
|
||||||
# PD Drive parameters:
|
# PD Drive parameters:
|
||||||
control_type = 'P'
|
control_type = 'P'
|
||||||
# PD Drive parameters:
|
# PD Drive parameters:
|
||||||
stiffness = {'hip_yaw': 200,
|
stiffness = {'hip_yaw': 150,
|
||||||
'hip_roll': 200,
|
'hip_roll': 150,
|
||||||
'hip_pitch': 200,
|
'hip_pitch': 150,
|
||||||
'knee': 300,
|
'knee': 200,
|
||||||
'ankle': 40,
|
'ankle': 40,
|
||||||
'torso': 300,
|
'torso': 300,
|
||||||
'shoulder': 100,
|
'shoulder': 150,
|
||||||
"elbow":100,
|
"elbow":100,
|
||||||
} # [N*m/rad]
|
} # [N*m/rad]
|
||||||
damping = { 'hip_yaw': 5,
|
damping = { 'hip_yaw': 2,
|
||||||
'hip_roll': 5,
|
'hip_roll': 2,
|
||||||
'hip_pitch': 5,
|
'hip_pitch': 2,
|
||||||
'knee': 6,
|
'knee': 4,
|
||||||
'ankle': 2,
|
'ankle': 2,
|
||||||
'torso': 6,
|
'torso': 6,
|
||||||
'shoulder': 2,
|
'shoulder': 2,
|
||||||
@ -63,30 +74,46 @@ class H1RoughCfg( LeggedRobotCfg ):
|
|||||||
foot_name = "ankle"
|
foot_name = "ankle"
|
||||||
penalize_contacts_on = ["hip", "knee"]
|
penalize_contacts_on = ["hip", "knee"]
|
||||||
terminate_after_contacts_on = ["pelvis"]
|
terminate_after_contacts_on = ["pelvis"]
|
||||||
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
|
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
|
||||||
flip_visual_attachments = False
|
flip_visual_attachments = False
|
||||||
|
|
||||||
class rewards( LeggedRobotCfg.rewards ):
|
class rewards( LeggedRobotCfg.rewards ):
|
||||||
soft_dof_pos_limit = 0.9
|
soft_dof_pos_limit = 0.9
|
||||||
base_height_target = 0.98
|
base_height_target = 1.05
|
||||||
class scales( LeggedRobotCfg.rewards.scales ):
|
class scales( LeggedRobotCfg.rewards.scales ):
|
||||||
tracking_lin_vel = 1.0
|
tracking_lin_vel = 1.0
|
||||||
tracking_ang_vel = 0.5
|
tracking_ang_vel = 0.5
|
||||||
lin_vel_z = -2.0
|
lin_vel_z = -2.0
|
||||||
ang_vel_xy = -1.0
|
ang_vel_xy = -0.05
|
||||||
orientation = -1.0
|
orientation = -1.0
|
||||||
base_height = -100.0
|
base_height = -10.0
|
||||||
dof_acc = -3.5e-8
|
dof_acc = -2.5e-7
|
||||||
feet_air_time = 1.0
|
feet_air_time = 0.0
|
||||||
collision = 0.0
|
collision = -1.0
|
||||||
action_rate = -0.01
|
action_rate = -0.01
|
||||||
torques = 0.0
|
torques = 0.0
|
||||||
dof_pos_limits = -10.0
|
dof_pos_limits = -5.0
|
||||||
|
alive = 0.15
|
||||||
|
hip_pos = -1.0
|
||||||
|
contact_no_vel = -0.2
|
||||||
|
feet_swing_height = -20.0
|
||||||
|
contact = 0.18
|
||||||
|
|
||||||
class H1RoughCfgPPO( LeggedRobotCfgPPO ):
|
class H1RoughCfgPPO( LeggedRobotCfgPPO ):
|
||||||
|
class policy:
|
||||||
|
init_noise_std = 0.8
|
||||||
|
actor_hidden_dims = [32]
|
||||||
|
critic_hidden_dims = [32]
|
||||||
|
activation = 'elu' # can be elu, relu, selu, crelu, lrelu, tanh, sigmoid
|
||||||
|
# only for 'ActorCriticRecurrent':
|
||||||
|
rnn_type = 'lstm'
|
||||||
|
rnn_hidden_size = 64
|
||||||
|
rnn_num_layers = 1
|
||||||
class algorithm( LeggedRobotCfgPPO.algorithm ):
|
class algorithm( LeggedRobotCfgPPO.algorithm ):
|
||||||
entropy_coef = 0.01
|
entropy_coef = 0.01
|
||||||
class runner( LeggedRobotCfgPPO.runner ):
|
class runner( LeggedRobotCfgPPO.runner ):
|
||||||
|
policy_class_name = "ActorCriticRecurrent"
|
||||||
|
max_iterations = 10000
|
||||||
run_name = ''
|
run_name = ''
|
||||||
experiment_name = 'h1'
|
experiment_name = 'h1'
|
||||||
|
|
||||||
|
124
legged_gym/envs/h1/h1_env.py
Normal file
124
legged_gym/envs/h1/h1_env.py
Normal file
@ -0,0 +1,124 @@
|
|||||||
|
|
||||||
|
from legged_gym.envs.base.legged_robot import LeggedRobot
|
||||||
|
|
||||||
|
from isaacgym.torch_utils import *
|
||||||
|
from isaacgym import gymtorch, gymapi, gymutil
|
||||||
|
import torch
|
||||||
|
|
||||||
|
class H1Robot(LeggedRobot):
|
||||||
|
|
||||||
|
def _get_noise_scale_vec(self, cfg):
|
||||||
|
""" Sets a vector used to scale the noise added to the observations.
|
||||||
|
[NOTE]: Must be adapted when changing the observations structure
|
||||||
|
|
||||||
|
Args:
|
||||||
|
cfg (Dict): Environment config file
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
[torch.Tensor]: Vector of scales used to multiply a uniform distribution in [-1, 1]
|
||||||
|
"""
|
||||||
|
noise_vec = torch.zeros_like(self.obs_buf[0])
|
||||||
|
self.add_noise = self.cfg.noise.add_noise
|
||||||
|
noise_scales = self.cfg.noise.noise_scales
|
||||||
|
noise_level = self.cfg.noise.noise_level
|
||||||
|
noise_vec[:3] = noise_scales.ang_vel * noise_level * self.obs_scales.ang_vel
|
||||||
|
noise_vec[3:6] = noise_scales.gravity * noise_level
|
||||||
|
noise_vec[6:9] = 0. # commands
|
||||||
|
noise_vec[9:9+self.num_actions] = noise_scales.dof_pos * noise_level * self.obs_scales.dof_pos
|
||||||
|
noise_vec[9+self.num_actions:9+2*self.num_actions] = noise_scales.dof_vel * noise_level * self.obs_scales.dof_vel
|
||||||
|
noise_vec[9+2*self.num_actions:9+3*self.num_actions] = 0. # previous actions
|
||||||
|
noise_vec[9+3*self.num_actions:9+3*self.num_actions+2] = 0. # sin/cos phase
|
||||||
|
|
||||||
|
return noise_vec
|
||||||
|
|
||||||
|
def _init_foot(self):
|
||||||
|
self.feet_num = len(self.feet_indices)
|
||||||
|
|
||||||
|
rigid_body_state = self.gym.acquire_rigid_body_state_tensor(self.sim)
|
||||||
|
self.rigid_body_states = gymtorch.wrap_tensor(rigid_body_state)
|
||||||
|
self.rigid_body_states_view = self.rigid_body_states.view(self.num_envs, -1, 13)
|
||||||
|
self.feet_state = self.rigid_body_states_view[:, self.feet_indices, :]
|
||||||
|
self.feet_pos = self.feet_state[:, :, :3]
|
||||||
|
self.feet_vel = self.feet_state[:, :, 7:10]
|
||||||
|
|
||||||
|
def _init_buffers(self):
|
||||||
|
super()._init_buffers()
|
||||||
|
self._init_foot()
|
||||||
|
|
||||||
|
def update_feet_state(self):
|
||||||
|
self.gym.refresh_rigid_body_state_tensor(self.sim)
|
||||||
|
|
||||||
|
self.feet_state = self.rigid_body_states_view[:, self.feet_indices, :]
|
||||||
|
self.feet_pos = self.feet_state[:, :, :3]
|
||||||
|
self.feet_vel = self.feet_state[:, :, 7:10]
|
||||||
|
|
||||||
|
def _post_physics_step_callback(self):
|
||||||
|
self.update_feet_state()
|
||||||
|
|
||||||
|
period = 0.8
|
||||||
|
offset = 0.5
|
||||||
|
self.phase = (self.episode_length_buf * self.dt) % period / period
|
||||||
|
self.phase_left = self.phase
|
||||||
|
self.phase_right = (self.phase + offset) % 1
|
||||||
|
self.leg_phase = torch.cat([self.phase_left.unsqueeze(1), self.phase_right.unsqueeze(1)], dim=-1)
|
||||||
|
|
||||||
|
return super()._post_physics_step_callback()
|
||||||
|
|
||||||
|
|
||||||
|
def compute_observations(self):
|
||||||
|
""" Computes observations
|
||||||
|
"""
|
||||||
|
sin_phase = torch.sin(2 * np.pi * self.phase ).unsqueeze(1)
|
||||||
|
cos_phase = torch.cos(2 * np.pi * self.phase ).unsqueeze(1)
|
||||||
|
self.obs_buf = torch.cat(( self.base_ang_vel * self.obs_scales.ang_vel,
|
||||||
|
self.projected_gravity,
|
||||||
|
self.commands[:, :3] * self.commands_scale,
|
||||||
|
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
|
||||||
|
self.dof_vel * self.obs_scales.dof_vel,
|
||||||
|
self.actions,
|
||||||
|
sin_phase,
|
||||||
|
cos_phase
|
||||||
|
),dim=-1)
|
||||||
|
self.privileged_obs_buf = torch.cat(( self.base_lin_vel * self.obs_scales.lin_vel,
|
||||||
|
self.base_ang_vel * self.obs_scales.ang_vel,
|
||||||
|
self.projected_gravity,
|
||||||
|
self.commands[:, :3] * self.commands_scale,
|
||||||
|
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
|
||||||
|
self.dof_vel * self.obs_scales.dof_vel,
|
||||||
|
self.actions,
|
||||||
|
sin_phase,
|
||||||
|
cos_phase
|
||||||
|
),dim=-1)
|
||||||
|
# add perceptive inputs if not blind
|
||||||
|
# add noise if needed
|
||||||
|
if self.add_noise:
|
||||||
|
self.obs_buf += (2 * torch.rand_like(self.obs_buf) - 1) * self.noise_scale_vec
|
||||||
|
|
||||||
|
|
||||||
|
def _reward_contact(self):
|
||||||
|
res = torch.zeros(self.num_envs, dtype=torch.float, device=self.device)
|
||||||
|
for i in range(self.feet_num):
|
||||||
|
is_stance = self.leg_phase[:, i] < 0.55
|
||||||
|
contact = self.contact_forces[:, self.feet_indices[i], 2] > 1
|
||||||
|
res += ~(contact ^ is_stance)
|
||||||
|
return res
|
||||||
|
|
||||||
|
def _reward_feet_swing_height(self):
|
||||||
|
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
|
||||||
|
pos_error = torch.square(self.feet_pos[:, :, 2] - 0.08) * ~contact
|
||||||
|
return torch.sum(pos_error, dim=(1))
|
||||||
|
|
||||||
|
def _reward_alive(self):
|
||||||
|
# Reward for staying alive
|
||||||
|
return 1.0
|
||||||
|
|
||||||
|
def _reward_contact_no_vel(self):
|
||||||
|
# Penalize contact with no velocity
|
||||||
|
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
|
||||||
|
contact_feet_vel = self.feet_vel * contact.unsqueeze(-1)
|
||||||
|
penalize = torch.square(contact_feet_vel[:, :, :3])
|
||||||
|
return torch.sum(penalize, dim=(1,2))
|
||||||
|
|
||||||
|
def _reward_hip_pos(self):
|
||||||
|
return torch.sum(torch.square(self.dof_pos[:,[0,1,5,6]]), dim=1)
|
||||||
|
|
@ -4,20 +4,20 @@ from legged_gym.envs.base.legged_robot_config import LeggedRobotCfg, LeggedRobot
|
|||||||
class H1_2RoughCfg(LeggedRobotCfg):
|
class H1_2RoughCfg(LeggedRobotCfg):
|
||||||
|
|
||||||
class init_state(LeggedRobotCfg.init_state):
|
class init_state(LeggedRobotCfg.init_state):
|
||||||
pos = [0.0, 0.0, 1.0] # x,y,z [m]
|
pos = [0.0, 0.0, 1.05] # x,y,z [m]
|
||||||
default_joint_angles = { # = target angles [rad] when action = 0.0
|
default_joint_angles = { # = target angles [rad] when action = 0.0
|
||||||
'left_hip_yaw_joint': 0,
|
'left_hip_yaw_joint': 0,
|
||||||
'left_hip_roll_joint': 0,
|
'left_hip_roll_joint': 0,
|
||||||
'left_hip_pitch_joint': -0.6,
|
'left_hip_pitch_joint': -0.16,
|
||||||
'left_knee_joint': 1.2,
|
'left_knee_joint': 0.36,
|
||||||
'left_ankle_pitch_joint': -0.6,
|
'left_ankle_pitch_joint': -0.2,
|
||||||
'left_ankle_roll_joint': 0.0,
|
'left_ankle_roll_joint': 0.0,
|
||||||
|
|
||||||
'right_hip_yaw_joint': 0,
|
'right_hip_yaw_joint': 0,
|
||||||
'right_hip_roll_joint': 0,
|
'right_hip_roll_joint': 0,
|
||||||
'right_hip_pitch_joint': -0.6,
|
'right_hip_pitch_joint': -0.16,
|
||||||
'right_knee_joint': 1.2,
|
'right_knee_joint': 0.36,
|
||||||
'right_ankle_pitch_joint': -0.6,
|
'right_ankle_pitch_joint': -0.2,
|
||||||
'right_ankle_roll_joint': 0.0,
|
'right_ankle_roll_joint': 0.0,
|
||||||
|
|
||||||
'torso_joint': 0,
|
'torso_joint': 0,
|
||||||
@ -34,9 +34,11 @@ class H1_2RoughCfg(LeggedRobotCfg):
|
|||||||
}
|
}
|
||||||
|
|
||||||
class env(LeggedRobotCfg.env):
|
class env(LeggedRobotCfg.env):
|
||||||
num_actions = 21
|
# 3 + 3 + 3 + 12 + 12 + 12 + 2 = 47
|
||||||
num_observations = 12 + num_actions * 3
|
num_observations = 47
|
||||||
num_envs = 8192
|
num_privileged_obs = 50
|
||||||
|
num_actions = 12
|
||||||
|
|
||||||
|
|
||||||
class control(LeggedRobotCfg.control):
|
class control(LeggedRobotCfg.control):
|
||||||
# PD Drive parameters:
|
# PD Drive parameters:
|
||||||
@ -47,74 +49,82 @@ class H1_2RoughCfg(LeggedRobotCfg):
|
|||||||
'hip_roll_joint': 200.,
|
'hip_roll_joint': 200.,
|
||||||
'hip_pitch_joint': 200.,
|
'hip_pitch_joint': 200.,
|
||||||
'knee_joint': 300.,
|
'knee_joint': 300.,
|
||||||
'ankle_pitch_joint': 60.,
|
'ankle_pitch_joint': 40.,
|
||||||
'ankle_roll_joint': 40.,
|
'ankle_roll_joint': 40.,
|
||||||
'torso_joint': 600.,
|
|
||||||
'shoulder_pitch_joint': 80.,
|
|
||||||
'shoulder_roll_joint': 80.,
|
|
||||||
'shoulder_yaw_joint': 40.,
|
|
||||||
'elbow_pitch_joint': 60.,
|
|
||||||
} # [N*m/rad]
|
} # [N*m/rad]
|
||||||
damping = {
|
damping = {
|
||||||
'hip_yaw_joint': 5.0,
|
'hip_yaw_joint': 2.5,
|
||||||
'hip_roll_joint': 5.0,
|
'hip_roll_joint': 2.5,
|
||||||
'hip_pitch_joint': 5.0,
|
'hip_pitch_joint': 2.5,
|
||||||
'knee_joint': 7.5,
|
'knee_joint': 4,
|
||||||
'ankle_pitch_joint': 1.0,
|
'ankle_pitch_joint': 2.0,
|
||||||
'ankle_roll_joint': 0.3,
|
'ankle_roll_joint': 2.0,
|
||||||
'torso_joint': 15.0,
|
|
||||||
'shoulder_pitch_joint': 2.0,
|
|
||||||
'shoulder_roll_joint': 2.0,
|
|
||||||
'shoulder_yaw_joint': 1.0,
|
|
||||||
'elbow_pitch_joint': 1.0,
|
|
||||||
} # [N*m/rad] # [N*m*s/rad]
|
} # [N*m/rad] # [N*m*s/rad]
|
||||||
# action scale: target angle = actionScale * action + defaultAngle
|
# action scale: target angle = actionScale * action + defaultAngle
|
||||||
action_scale = 0.25
|
action_scale = 0.25
|
||||||
# decimation: Number of control action updates @ sim DT per policy DT
|
# decimation: Number of control action updates @ sim DT per policy DT
|
||||||
decimation = 10
|
decimation = 8
|
||||||
|
|
||||||
class asset(LeggedRobotCfg.asset):
|
|
||||||
file = '{LEGGED_GYM_ROOT_DIR}/resources/robots/h1_2/h1_2_simplified.urdf'
|
|
||||||
name = "h1_2"
|
|
||||||
foot_name = "ankle_roll"
|
|
||||||
penalize_contacts_on = []
|
|
||||||
terminate_after_contacts_on = []
|
|
||||||
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
|
|
||||||
flip_visual_attachments = False
|
|
||||||
armature = 6e-4 # stablize semi-euler integration for end effectors
|
|
||||||
|
|
||||||
class sim(LeggedRobotCfg.sim):
|
class sim(LeggedRobotCfg.sim):
|
||||||
dt = 0.002 # stablize semi-euler integration for end effectors
|
dt = 0.0025
|
||||||
|
|
||||||
|
class domain_rand(LeggedRobotCfg.domain_rand):
|
||||||
|
randomize_friction = True
|
||||||
|
friction_range = [0.1, 1.25]
|
||||||
|
randomize_base_mass = True
|
||||||
|
added_mass_range = [-1., 3.]
|
||||||
|
push_robots = True
|
||||||
|
push_interval_s = 5
|
||||||
|
max_push_vel_xy = 1.5
|
||||||
|
|
||||||
|
class asset(LeggedRobotCfg.asset):
|
||||||
|
file = '{LEGGED_GYM_ROOT_DIR}/resources/robots/h1_2/h1_2_12dof.urdf'
|
||||||
|
name = "h1_2"
|
||||||
|
foot_name = "ankle_roll"
|
||||||
|
penalize_contacts_on = ["hip", "knee"]
|
||||||
|
terminate_after_contacts_on = ["pelvis"]
|
||||||
|
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
|
||||||
|
flip_visual_attachments = False
|
||||||
|
armature = 1e-3
|
||||||
|
|
||||||
class rewards(LeggedRobotCfg.rewards):
|
class rewards(LeggedRobotCfg.rewards):
|
||||||
soft_dof_pos_limit = 0.9
|
soft_dof_pos_limit = 0.9
|
||||||
base_height_target = 0.98
|
base_height_target = 1.0
|
||||||
|
|
||||||
class scales(LeggedRobotCfg.rewards.scales):
|
class scales(LeggedRobotCfg.rewards.scales):
|
||||||
tracking_lin_vel = 1.0
|
tracking_lin_vel = 1.0
|
||||||
tracking_ang_vel = 0.5
|
tracking_ang_vel = 0.5
|
||||||
lin_vel_z = -0.2
|
lin_vel_z = -2.0
|
||||||
ang_vel_xy = -0.1
|
ang_vel_xy = -0.05
|
||||||
orientation = -0.1
|
orientation = -1.0
|
||||||
base_height = -10.0
|
base_height = -10.0
|
||||||
dof_acc = -3e-8
|
dof_acc = -2.5e-7
|
||||||
feet_air_time = 1.0
|
dof_vel = -1e-3
|
||||||
|
feet_air_time = 0.0
|
||||||
collision = 0.0
|
collision = 0.0
|
||||||
action_rate = -0.1
|
action_rate = -0.01
|
||||||
dof_pos_limits = -10.0
|
dof_pos_limits = -5.0
|
||||||
|
alive = 0.15
|
||||||
only_positive_rewards = False # if true negative total rewards are clipped at zero (avoids early termination problems)
|
hip_pos = -1.0
|
||||||
|
contact_no_vel = -0.2
|
||||||
class normalization(LeggedRobotCfg.normalization):
|
feet_swing_height = -20.0
|
||||||
clip_actions = 10.0
|
contact = 0.18
|
||||||
|
|
||||||
|
|
||||||
class H1_2RoughCfgPPO(LeggedRobotCfgPPO):
|
class H1_2RoughCfgPPO(LeggedRobotCfgPPO):
|
||||||
|
class policy:
|
||||||
class policy(LeggedRobotCfgPPO.policy):
|
init_noise_std = 0.8
|
||||||
init_noise_std = 0.3
|
actor_hidden_dims = [32]
|
||||||
activation = 'tanh'
|
critic_hidden_dims = [32]
|
||||||
|
activation = 'elu' # can be elu, relu, selu, crelu, lrelu, tanh, sigmoid
|
||||||
class runner(LeggedRobotCfgPPO.runner):
|
# only for 'ActorCriticRecurrent':
|
||||||
|
rnn_type = 'lstm'
|
||||||
|
rnn_hidden_size = 64
|
||||||
|
rnn_num_layers = 1
|
||||||
|
class algorithm( LeggedRobotCfgPPO.algorithm ):
|
||||||
|
entropy_coef = 0.01
|
||||||
|
class runner( LeggedRobotCfgPPO.runner ):
|
||||||
|
policy_class_name = "ActorCriticRecurrent"
|
||||||
|
max_iterations = 10000
|
||||||
run_name = ''
|
run_name = ''
|
||||||
experiment_name = 'h1_2'
|
experiment_name = 'h1_2'
|
124
legged_gym/envs/h1_2/h1_2_env.py
Normal file
124
legged_gym/envs/h1_2/h1_2_env.py
Normal file
@ -0,0 +1,124 @@
|
|||||||
|
|
||||||
|
from legged_gym.envs.base.legged_robot import LeggedRobot
|
||||||
|
|
||||||
|
from isaacgym.torch_utils import *
|
||||||
|
from isaacgym import gymtorch, gymapi, gymutil
|
||||||
|
import torch
|
||||||
|
|
||||||
|
class H1_2Robot(LeggedRobot):
|
||||||
|
|
||||||
|
def _get_noise_scale_vec(self, cfg):
|
||||||
|
""" Sets a vector used to scale the noise added to the observations.
|
||||||
|
[NOTE]: Must be adapted when changing the observations structure
|
||||||
|
|
||||||
|
Args:
|
||||||
|
cfg (Dict): Environment config file
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
[torch.Tensor]: Vector of scales used to multiply a uniform distribution in [-1, 1]
|
||||||
|
"""
|
||||||
|
noise_vec = torch.zeros_like(self.obs_buf[0])
|
||||||
|
self.add_noise = self.cfg.noise.add_noise
|
||||||
|
noise_scales = self.cfg.noise.noise_scales
|
||||||
|
noise_level = self.cfg.noise.noise_level
|
||||||
|
noise_vec[:3] = noise_scales.ang_vel * noise_level * self.obs_scales.ang_vel
|
||||||
|
noise_vec[3:6] = noise_scales.gravity * noise_level
|
||||||
|
noise_vec[6:9] = 0. # commands
|
||||||
|
noise_vec[9:9+self.num_actions] = noise_scales.dof_pos * noise_level * self.obs_scales.dof_pos
|
||||||
|
noise_vec[9+self.num_actions:9+2*self.num_actions] = noise_scales.dof_vel * noise_level * self.obs_scales.dof_vel
|
||||||
|
noise_vec[9+2*self.num_actions:9+3*self.num_actions] = 0. # previous actions
|
||||||
|
noise_vec[9+3*self.num_actions:9+3*self.num_actions+2] = 0. # sin/cos phase
|
||||||
|
|
||||||
|
return noise_vec
|
||||||
|
|
||||||
|
def _init_foot(self):
|
||||||
|
self.feet_num = len(self.feet_indices)
|
||||||
|
|
||||||
|
rigid_body_state = self.gym.acquire_rigid_body_state_tensor(self.sim)
|
||||||
|
self.rigid_body_states = gymtorch.wrap_tensor(rigid_body_state)
|
||||||
|
self.rigid_body_states_view = self.rigid_body_states.view(self.num_envs, -1, 13)
|
||||||
|
self.feet_state = self.rigid_body_states_view[:, self.feet_indices, :]
|
||||||
|
self.feet_pos = self.feet_state[:, :, :3]
|
||||||
|
self.feet_vel = self.feet_state[:, :, 7:10]
|
||||||
|
|
||||||
|
def _init_buffers(self):
|
||||||
|
super()._init_buffers()
|
||||||
|
self._init_foot()
|
||||||
|
|
||||||
|
def update_feet_state(self):
|
||||||
|
self.gym.refresh_rigid_body_state_tensor(self.sim)
|
||||||
|
|
||||||
|
self.feet_state = self.rigid_body_states_view[:, self.feet_indices, :]
|
||||||
|
self.feet_pos = self.feet_state[:, :, :3]
|
||||||
|
self.feet_vel = self.feet_state[:, :, 7:10]
|
||||||
|
|
||||||
|
def _post_physics_step_callback(self):
|
||||||
|
self.update_feet_state()
|
||||||
|
|
||||||
|
period = 0.8
|
||||||
|
offset = 0.5
|
||||||
|
self.phase = (self.episode_length_buf * self.dt) % period / period
|
||||||
|
self.phase_left = self.phase
|
||||||
|
self.phase_right = (self.phase + offset) % 1
|
||||||
|
self.leg_phase = torch.cat([self.phase_left.unsqueeze(1), self.phase_right.unsqueeze(1)], dim=-1)
|
||||||
|
|
||||||
|
return super()._post_physics_step_callback()
|
||||||
|
|
||||||
|
|
||||||
|
def compute_observations(self):
|
||||||
|
""" Computes observations
|
||||||
|
"""
|
||||||
|
sin_phase = torch.sin(2 * np.pi * self.phase ).unsqueeze(1)
|
||||||
|
cos_phase = torch.cos(2 * np.pi * self.phase ).unsqueeze(1)
|
||||||
|
self.obs_buf = torch.cat(( self.base_ang_vel * self.obs_scales.ang_vel,
|
||||||
|
self.projected_gravity,
|
||||||
|
self.commands[:, :3] * self.commands_scale,
|
||||||
|
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
|
||||||
|
self.dof_vel * self.obs_scales.dof_vel,
|
||||||
|
self.actions,
|
||||||
|
sin_phase,
|
||||||
|
cos_phase
|
||||||
|
),dim=-1)
|
||||||
|
self.privileged_obs_buf = torch.cat(( self.base_lin_vel * self.obs_scales.lin_vel,
|
||||||
|
self.base_ang_vel * self.obs_scales.ang_vel,
|
||||||
|
self.projected_gravity,
|
||||||
|
self.commands[:, :3] * self.commands_scale,
|
||||||
|
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos,
|
||||||
|
self.dof_vel * self.obs_scales.dof_vel,
|
||||||
|
self.actions,
|
||||||
|
sin_phase,
|
||||||
|
cos_phase
|
||||||
|
),dim=-1)
|
||||||
|
# add perceptive inputs if not blind
|
||||||
|
# add noise if needed
|
||||||
|
if self.add_noise:
|
||||||
|
self.obs_buf += (2 * torch.rand_like(self.obs_buf) - 1) * self.noise_scale_vec
|
||||||
|
|
||||||
|
|
||||||
|
def _reward_contact(self):
|
||||||
|
res = torch.zeros(self.num_envs, dtype=torch.float, device=self.device)
|
||||||
|
for i in range(self.feet_num):
|
||||||
|
is_stance = self.leg_phase[:, i] < 0.55
|
||||||
|
contact = self.contact_forces[:, self.feet_indices[i], 2] > 1
|
||||||
|
res += ~(contact ^ is_stance)
|
||||||
|
return res
|
||||||
|
|
||||||
|
def _reward_feet_swing_height(self):
|
||||||
|
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
|
||||||
|
pos_error = torch.square(self.feet_pos[:, :, 2] - 0.08) * ~contact
|
||||||
|
return torch.sum(pos_error, dim=(1))
|
||||||
|
|
||||||
|
def _reward_alive(self):
|
||||||
|
# Reward for staying alive
|
||||||
|
return 1.0
|
||||||
|
|
||||||
|
def _reward_contact_no_vel(self):
|
||||||
|
# Penalize contact with no velocity
|
||||||
|
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
|
||||||
|
contact_feet_vel = self.feet_vel * contact.unsqueeze(-1)
|
||||||
|
penalize = torch.square(contact_feet_vel[:, :, :3])
|
||||||
|
return torch.sum(penalize, dim=(1,2))
|
||||||
|
|
||||||
|
def _reward_hip_pos(self):
|
||||||
|
return torch.sum(torch.square(self.dof_pos[:,[0,2,6,8]]), dim=1)
|
||||||
|
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
File diff suppressed because it is too large
Load Diff
30
resources/robots/g1_description/README.md
Normal file
30
resources/robots/g1_description/README.md
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
# Unitree G1 Description (URDF & MJCF)
|
||||||
|
|
||||||
|
## Overview
|
||||||
|
|
||||||
|
This package includes a universal humanoid robot description (URDF & MJCF) for the [Unitree G1](https://www.unitree.com/g1/), developed by [Unitree Robotics](https://www.unitree.com/).
|
||||||
|
|
||||||
|
MJCF/URDF for the G1 robot:
|
||||||
|
|
||||||
|
| MJCF/URDF file name | `mode_machine` | Hip roll reduction ratio | Update status | dof#leg | dof#waist | dof#arm | dof#hand |
|
||||||
|
| ----------------------------- | :------------: | :----------------------: | ------------- | :-----: | :-------: | :-----: | :------: |
|
||||||
|
| `g1_23dof` | 1 | 14.5 | Beta | 6*2 | 1 | 5*2 | 0 |
|
||||||
|
| `g1_29dof` | 2 | 14.5 | Beta | 6*2 | 3 | 7*2 | 0 |
|
||||||
|
| `g1_29dof_with_hand` | 2 | 14.5 | Beta | 6*2 | 3 | 7*2 | 7*2 |
|
||||||
|
| `g1_29dof_lock_waist` | 3 | 14.5 | Beta | 6*2 | 1 | 7*2 | 0 |
|
||||||
|
| `g1_23dof_rev_1_0` | 4 | 22.5 | Up-to-date | 6*2 | 1 | 5*2 | 0 |
|
||||||
|
| `g1_29dof_rev_1_0` | 5 | 22.5 | Up-to-date | 6*2 | 3 | 7*2 | 0 |
|
||||||
|
| `g1_29dof_with_hand_rev_1_0` | 5 | 22.5 | Up-to-date | 6*2 | 3 | 7*2 | 7*2 |
|
||||||
|
| `g1_29dof_lock_waist_rev_1_0` | 6 | 22.5 | Up-to-date | 6*2 | 1 | 7*2 | 0 |
|
||||||
|
| `g1_dual_arm` | 9 | null | Up-to-date | 0 | 0 | 7*2 | 0 |
|
||||||
|
|
||||||
|
## Visulization with [MuJoCo](https://github.com/google-deepmind/mujoco)
|
||||||
|
|
||||||
|
1. Open MuJoCo Viewer
|
||||||
|
|
||||||
|
```bash
|
||||||
|
pip install mujoco
|
||||||
|
python -m mujoco.viewer
|
||||||
|
```
|
||||||
|
|
||||||
|
2. Drag and drop the MJCF/URDF model file (`g1_XXX.xml`/`g1_XXX.urdf`) to the MuJoCo Viewer.
|
854
resources/robots/g1_description/g1_12dof.urdf
Normal file
854
resources/robots/g1_description/g1_12dof.urdf
Normal file
@ -0,0 +1,854 @@
|
|||||||
|
<robot name="g1_12dof">
|
||||||
|
<mujoco>
|
||||||
|
<compiler meshdir="meshes" discardvisual="false"/>
|
||||||
|
</mujoco>
|
||||||
|
|
||||||
|
<!-- [CAUTION] uncomment when convert to mujoco -->
|
||||||
|
<!-- <link name="world"></link>
|
||||||
|
<joint name="floating_base_joint" type="floating">
|
||||||
|
<parent link="world"/>
|
||||||
|
<child link="pelvis"/>
|
||||||
|
</joint> -->
|
||||||
|
|
||||||
|
<link name="pelvis">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 -0.07605" rpy="0 0 0"/>
|
||||||
|
<mass value="3.813"/>
|
||||||
|
<inertia ixx="0.010549" ixy="0" ixz="2.1E-06" iyy="0.0093089" iyz="0" izz="0.0079184"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<link name="pelvis_contour_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="pelvis_contour_joint" type="fixed">
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="pelvis_contour_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Legs -->
|
||||||
|
<link name="left_hip_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002741 0.047791 -0.02606" rpy="0 0 0"/>
|
||||||
|
<mass value="1.35"/>
|
||||||
|
<inertia ixx="0.001811" ixy="3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="0.000171" izz="0.0012812"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.064452 -0.1027" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="left_hip_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_hip_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.029812 -0.001045 -0.087934" rpy="0 0 0"/>
|
||||||
|
<mass value="1.52"/>
|
||||||
|
<inertia ixx="0.0023773" ixy="-3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="1.84E-05" izz="0.0016595"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||||
|
<parent link="left_hip_pitch_link"/>
|
||||||
|
<child link="left_hip_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.5236" upper="2.9671" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_hip_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.057709 -0.010981 -0.15078" rpy="0 0 0"/>
|
||||||
|
<mass value="1.702"/>
|
||||||
|
<inertia ixx="0.0057774" ixy="-0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="-0.0007072" izz="0.003149"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||||
|
<parent link="left_hip_roll_link"/>
|
||||||
|
<child link="left_hip_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_knee_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005457 0.003964 -0.12074" rpy="0 0 0"/>
|
||||||
|
<mass value="1.932"/>
|
||||||
|
<inertia ixx="0.011329" ixy="4.82E-05" ixz="-4.49E-05" iyy="0.011277" iyz="-0.0007146" izz="0.0015168"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_knee_joint" type="revolute">
|
||||||
|
<origin xyz="-0.078273 0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||||
|
<parent link="left_hip_yaw_link"/>
|
||||||
|
<child link="left_knee_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_ankle_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||||
|
<mass value="0.074"/>
|
||||||
|
<inertia ixx="0.01" ixy="0" ixz="-2.9E-06" iyy="0.01" iyz="0" izz="0.01"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_ankle_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 -9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||||
|
<parent link="left_knee_link"/>
|
||||||
|
<child link="left_ankle_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_ankle_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||||
|
<mass value="0.608"/>
|
||||||
|
<inertia ixx="0.01" ixy="2E-07" ixz="8.91E-05" iyy="0.01" iyz="-1E-07" izz="0.01"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_ankle_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||||
|
<parent link="left_ankle_pitch_link"/>
|
||||||
|
<child link="left_ankle_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002741 -0.047791 -0.02606" rpy="0 0 0"/>
|
||||||
|
<mass value="1.35"/>
|
||||||
|
<inertia ixx="0.001811" ixy="-3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="-0.000171" izz="0.0012812"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.064452 -0.1027" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="right_hip_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.029812 0.001045 -0.087934" rpy="0 0 0"/>
|
||||||
|
<mass value="1.52"/>
|
||||||
|
<inertia ixx="0.0023773" ixy="3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="-1.84E-05" izz="0.0016595"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||||
|
<parent link="right_hip_pitch_link"/>
|
||||||
|
<child link="right_hip_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-2.9671" upper="0.5236" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.057709 0.010981 -0.15078" rpy="0 0 0"/>
|
||||||
|
<mass value="1.702"/>
|
||||||
|
<inertia ixx="0.0057774" ixy="0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="0.0007072" izz="0.003149"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||||
|
<parent link="right_hip_roll_link"/>
|
||||||
|
<child link="right_hip_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_knee_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005457 -0.003964 -0.12074" rpy="0 0 0"/>
|
||||||
|
<mass value="1.932"/>
|
||||||
|
<inertia ixx="0.011329" ixy="-4.82E-05" ixz="4.49E-05" iyy="0.011277" iyz="0.0007146" izz="0.0015168"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_knee_joint" type="revolute">
|
||||||
|
<origin xyz="-0.078273 -0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||||
|
<parent link="right_hip_yaw_link"/>
|
||||||
|
<child link="right_knee_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_ankle_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||||
|
<mass value="0.074"/>
|
||||||
|
<inertia ixx="0.01" ixy="0" ixz="-2.9E-06" iyy="0.01" iyz="0" izz="0.01"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_ankle_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||||
|
<parent link="right_knee_link"/>
|
||||||
|
<child link="right_ankle_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_ankle_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||||
|
<mass value="0.608"/>
|
||||||
|
<inertia ixx="0.01" ixy="-2E-07" ixz="8.91E-05" iyy="0.01" iyz="1E-07" izz="0.01"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_ankle_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||||
|
<parent link="right_ankle_pitch_link"/>
|
||||||
|
<child link="right_ankle_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Torso -->
|
||||||
|
<joint name="waist_yaw_joint" type="fixed">
|
||||||
|
<origin xyz="-0.0039635 0 0.044" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="torso_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="torso_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.000931 0.000346 0.15082" rpy="0 0 0"/>
|
||||||
|
<mass value="6.78"/>
|
||||||
|
<inertia ixx="0.05905" ixy="3.3302E-05" ixz="-0.0017715" iyy="0.047014" iyz="-2.2399E-05" izz="0.025652"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link_23dof_rev_1_0.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link_23dof_rev_1_0.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- LOGO -->
|
||||||
|
<joint name="logo_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="logo_link"/>
|
||||||
|
</joint>
|
||||||
|
<link name="logo_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Head -->
|
||||||
|
<link name="head_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005267 0.000299 0.449869" rpy="0 0 0"/>
|
||||||
|
<mass value="1.036"/>
|
||||||
|
<inertia ixx="0.004085051" ixy="-2.543E-06" ixz="-6.9455E-05" iyy="0.004185212" iyz="-3.726E-06" izz="0.001807911"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="head_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="head_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- IMU -->
|
||||||
|
<link name="imu_in_torso"></link>
|
||||||
|
<joint name="imu_in_torso_joint" type="fixed">
|
||||||
|
<origin xyz="-0.03959 -0.00224 0.14792" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="imu_in_torso"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="imu_in_pelvis"></link>
|
||||||
|
<joint name="imu_in_pelvis_joint" type="fixed">
|
||||||
|
<origin xyz="0.04525 0 -0.08339" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="imu_in_pelvis"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- d435 -->
|
||||||
|
<link name="d435_link"></link>
|
||||||
|
<joint name="d435_joint" type="fixed">
|
||||||
|
<origin xyz="0.0576235 0.01753 0.42987" rpy="0 0.8307767239493009 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="d435_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- mid360 -->
|
||||||
|
<link name="mid360_link"></link>
|
||||||
|
<joint name="mid360_joint" type="fixed">
|
||||||
|
<origin xyz="0.0002835 0.00003 0.41618" rpy="0 0.04014257279586953 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="mid360_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Arm -->
|
||||||
|
<link name="left_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="-9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_pitch_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039563 0.10022 0.24778" rpy="0.27931 5.4949E-05 -0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="left_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="-1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="-5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_roll_joint" type="fixed">
|
||||||
|
<origin xyz="0 0.038 -0.013831" rpy="-0.27925 0 0"/>
|
||||||
|
<parent link="left_shoulder_pitch_link"/>
|
||||||
|
<child link="left_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-1.5882" upper="2.2515" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 -0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="-2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_yaw_joint" type="fixed">
|
||||||
|
<origin xyz="0 0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_roll_link"/>
|
||||||
|
<child link="left_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="-5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_elbow_joint" type="fixed">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_yaw_link"/>
|
||||||
|
<child link="left_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="left_wrist_roll_joint" type="fixed">
|
||||||
|
<origin xyz="0.100 0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="left_elbow_link"/>
|
||||||
|
<child link="left_wrist_roll_rubber_hand"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_wrist_roll_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.10794656650 0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||||
|
<mass value="0.35692864"/>
|
||||||
|
<inertia ixx="0.00019613494735" ixy="-0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="0.00000249774203" izz="0.00194181412808"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<link name="right_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 -0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="-2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 -0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_pitch_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039563 -0.10021 0.24778" rpy="-0.27931 5.4949E-05 0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="right_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 -0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 -0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_roll_joint" type="fixed">
|
||||||
|
<origin xyz="0 -0.038 -0.013831" rpy="0.27925 0 0"/>
|
||||||
|
<parent link="right_shoulder_pitch_link"/>
|
||||||
|
<child link="right_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-2.2515" upper="1.5882" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="-7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_yaw_joint" type="fixed">
|
||||||
|
<origin xyz="0 -0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_roll_link"/>
|
||||||
|
<child link="right_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 -0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="-6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_elbow_joint" type="fixed">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_yaw_link"/>
|
||||||
|
<child link="right_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="right_wrist_roll_joint" type="fixed">
|
||||||
|
<origin xyz="0.100 -0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="right_elbow_link"/>
|
||||||
|
<child link="right_wrist_roll_rubber_hand"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_wrist_roll_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.10794656650 -0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||||
|
<mass value="0.35692864"/>
|
||||||
|
<inertia ixx="0.00019613494735" ixy="0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="-0.00000249774203" izz="0.00194181412808"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
166
resources/robots/g1_description/g1_12dof.xml
Normal file
166
resources/robots/g1_description/g1_12dof.xml
Normal file
@ -0,0 +1,166 @@
|
|||||||
|
<mujoco model="g1_12dof">
|
||||||
|
<compiler angle="radian" meshdir="meshes/"/>
|
||||||
|
|
||||||
|
<statistic meansize="0.144785" extent="1.23314" center="0.025392 2.0634e-05 -0.245975"/>
|
||||||
|
<default>
|
||||||
|
<joint damping="0.001" armature="0.01" frictionloss="0.1"/>
|
||||||
|
</default>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="torso_link_23dof_rev_1_0" file="torso_link_23dof_rev_1_0.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_rubber_hand" file="left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_rubber_hand" file="right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0.0144905 0.000151462 0.144068" quat="0.999881 -0.000505543 -0.0154276 0.000328408" mass="17.7349" diaginertia="0.552723 0.454092 0.211762"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link_23dof_rev_1_0"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link_23dof_rev_1_0"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="-7.2e-06 0.10022 0.29178" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="7.72569e-07 0.141427 0.293195" quat="0.700213 0.0985001 0.700232 0.0983605" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<geom pos="3.73942e-07 0.14056 0.288961" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.00400139 0.146564 0.235962" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<geom pos="-4.10007e-06 0.146807 0.185762" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom pos="-4.10007e-06 0.146807 0.185762" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom pos="0.0157745 0.146808 0.105243" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom pos="0.0157745 0.146808 0.105243" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom pos="0.115774 0.148678 0.0952374" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||||
|
<geom pos="0.115774 0.148678 0.0952374" quat="1 3.00026e-05 2.74716e-05 -9.57958e-05" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||||
|
<geom pos="-7.2e-06 -0.10021 0.29178" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="7.72569e-07 -0.141417 0.293195" quat="0.700213 -0.0985001 0.700232 -0.0983605" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<geom pos="3.73942e-07 -0.14055 0.288961" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.00400139 -0.146554 0.235962" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<geom pos="-4.10007e-06 -0.146797 0.185762" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom pos="-4.10007e-06 -0.146797 0.185762" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom pos="0.0157745 -0.146798 0.105243" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom pos="0.0157745 -0.146798 0.105243" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom pos="0.115774 -0.148668 0.0952374" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||||
|
<geom pos="0.115774 -0.148668 0.0952374" quat="1 -3.00026e-05 2.74716e-05 9.57958e-05" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
</actuator>
|
||||||
|
</mujoco>
|
903
resources/robots/g1_description/g1_23dof.urdf
Normal file
903
resources/robots/g1_description/g1_23dof.urdf
Normal file
@ -0,0 +1,903 @@
|
|||||||
|
<robot name="g1_23dof">
|
||||||
|
<mujoco>
|
||||||
|
<compiler meshdir="meshes" discardvisual="false"/>
|
||||||
|
</mujoco>
|
||||||
|
|
||||||
|
<!-- [CAUTION] uncomment when convert to mujoco -->
|
||||||
|
<!-- <link name="world"></link>
|
||||||
|
<joint name="floating_base_joint" type="floating">
|
||||||
|
<parent link="world"/>
|
||||||
|
<child link="pelvis"/>
|
||||||
|
</joint> -->
|
||||||
|
|
||||||
|
<link name="pelvis">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 -0.07605" rpy="0 0 0"/>
|
||||||
|
<mass value="3.813"/>
|
||||||
|
<inertia ixx="0.010549" ixy="0" ixz="2.1E-06" iyy="0.0093089" iyz="0" izz="0.0079184"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<link name="pelvis_contour_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="pelvis_contour_joint" type="fixed">
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="pelvis_contour_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Legs -->
|
||||||
|
<link name="left_hip_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002741 0.047791 -0.02606" rpy="0 0 0"/>
|
||||||
|
<mass value="1.35"/>
|
||||||
|
<inertia ixx="0.001811" ixy="3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="0.000171" izz="0.0012812"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.064452 -0.1027" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="left_hip_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_hip_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.029812 -0.001045 -0.087934" rpy="0 0 0"/>
|
||||||
|
<mass value="1.52"/>
|
||||||
|
<inertia ixx="0.0023773" ixy="-3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="1.84E-05" izz="0.0016595"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||||
|
<parent link="left_hip_pitch_link"/>
|
||||||
|
<child link="left_hip_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.5236" upper="2.9671" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_hip_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.057709 -0.010981 -0.15078" rpy="0 0 0"/>
|
||||||
|
<mass value="1.702"/>
|
||||||
|
<inertia ixx="0.0057774" ixy="-0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="-0.0007072" izz="0.003149"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||||
|
<parent link="left_hip_roll_link"/>
|
||||||
|
<child link="left_hip_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_knee_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005457 0.003964 -0.12074" rpy="0 0 0"/>
|
||||||
|
<mass value="1.932"/>
|
||||||
|
<inertia ixx="0.011329" ixy="4.82E-05" ixz="-4.49E-05" iyy="0.011277" iyz="-0.0007146" izz="0.0015168"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_knee_joint" type="revolute">
|
||||||
|
<origin xyz="-0.078273 0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||||
|
<parent link="left_hip_yaw_link"/>
|
||||||
|
<child link="left_knee_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_ankle_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||||
|
<mass value="0.074"/>
|
||||||
|
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_ankle_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 -9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||||
|
<parent link="left_knee_link"/>
|
||||||
|
<child link="left_ankle_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_ankle_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||||
|
<mass value="0.608"/>
|
||||||
|
<inertia ixx="0.0002231" ixy="2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="-1E-07" izz="0.0016667"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_ankle_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||||
|
<parent link="left_ankle_pitch_link"/>
|
||||||
|
<child link="left_ankle_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002741 -0.047791 -0.02606" rpy="0 0 0"/>
|
||||||
|
<mass value="1.35"/>
|
||||||
|
<inertia ixx="0.001811" ixy="-3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="-0.000171" izz="0.0012812"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.064452 -0.1027" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="right_hip_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.029812 0.001045 -0.087934" rpy="0 0 0"/>
|
||||||
|
<mass value="1.52"/>
|
||||||
|
<inertia ixx="0.0023773" ixy="3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="-1.84E-05" izz="0.0016595"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||||
|
<parent link="right_hip_pitch_link"/>
|
||||||
|
<child link="right_hip_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-2.9671" upper="0.5236" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.057709 0.010981 -0.15078" rpy="0 0 0"/>
|
||||||
|
<mass value="1.702"/>
|
||||||
|
<inertia ixx="0.0057774" ixy="0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="0.0007072" izz="0.003149"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||||
|
<parent link="right_hip_roll_link"/>
|
||||||
|
<child link="right_hip_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_knee_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005457 -0.003964 -0.12074" rpy="0 0 0"/>
|
||||||
|
<mass value="1.932"/>
|
||||||
|
<inertia ixx="0.011329" ixy="-4.82E-05" ixz="4.49E-05" iyy="0.011277" iyz="0.0007146" izz="0.0015168"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_knee_joint" type="revolute">
|
||||||
|
<origin xyz="-0.078273 -0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||||
|
<parent link="right_hip_yaw_link"/>
|
||||||
|
<child link="right_knee_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_ankle_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||||
|
<mass value="0.074"/>
|
||||||
|
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_ankle_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||||
|
<parent link="right_knee_link"/>
|
||||||
|
<child link="right_ankle_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_ankle_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||||
|
<mass value="0.608"/>
|
||||||
|
<inertia ixx="0.0002231" ixy="-2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="1E-07" izz="0.0016667"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_ankle_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||||
|
<parent link="right_ankle_pitch_link"/>
|
||||||
|
<child link="right_ankle_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Torso -->
|
||||||
|
<link name="waist_yaw_fixed_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.003964 0 0.018769" rpy="0 0 0"/>
|
||||||
|
<mass value="0.244"/>
|
||||||
|
<inertia ixx="9.9587E-05" ixy="-1.833E-06" ixz="-1.2617E-05" iyy="0.00012411" iyz="-1.18E-07" izz="0.00015586"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/waist_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<joint name="waist_yaw_fixed_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="waist_yaw_fixed_link"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="waist_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="-0.0039635 0 0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="torso_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="torso_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002601 0.000257 0.153719" rpy="0 0 0"/>
|
||||||
|
<mass value="8.562"/>
|
||||||
|
<inertia ixx="0.065674966" ixy="-8.597E-05" ixz="-0.001737252" iyy="0.053535188" iyz="8.6899E-05" izz="0.030808125"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- LOGO -->
|
||||||
|
<joint name="logo_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="logo_link"/>
|
||||||
|
</joint>
|
||||||
|
<link name="logo_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Head -->
|
||||||
|
<link name="head_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005267 0.000299 0.449869" rpy="0 0 0"/>
|
||||||
|
<mass value="1.036"/>
|
||||||
|
<inertia ixx="0.004085051" ixy="-2.543E-06" ixz="-6.9455E-05" iyy="0.004185212" iyz="-3.726E-06" izz="0.001807911"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="head_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="head_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Waist Support -->
|
||||||
|
<link name="waist_support_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/waist_support_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/waist_support_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="waist_support_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="waist_support_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- IMU -->
|
||||||
|
<link name="imu_in_torso"></link>
|
||||||
|
<joint name="imu_in_torso_joint" type="fixed">
|
||||||
|
<origin xyz="-0.03959 -0.00224 0.13792" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="imu_in_torso"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="imu_in_pelvis"></link>
|
||||||
|
<joint name="imu_in_pelvis_joint" type="fixed">
|
||||||
|
<origin xyz="0.04525 0 -0.08339" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="imu_in_pelvis"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- d435 -->
|
||||||
|
<link name="d435_link"></link>
|
||||||
|
<joint name="d435_joint" type="fixed">
|
||||||
|
<origin xyz="0.0576235 0.01753 0.41987" rpy="0 0.8307767239493009 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="d435_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- mid360 -->
|
||||||
|
<link name="mid360_link"></link>
|
||||||
|
<joint name="mid360_joint" type="fixed">
|
||||||
|
<origin xyz="0.0002835 0.00003 0.40618" rpy="0 0.04014257279586953 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="mid360_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Arm -->
|
||||||
|
<link name="left_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="-9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.0039563 0.10022 0.23778" rpy="0.27931 5.4949E-05 -0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="left_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="-1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="-5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.038 -0.013831" rpy="-0.27925 0 0"/>
|
||||||
|
<parent link="left_shoulder_pitch_link"/>
|
||||||
|
<child link="left_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-1.5882" upper="2.2515" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 -0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="-2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_roll_link"/>
|
||||||
|
<child link="left_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="-5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_elbow_joint" type="revolute">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_yaw_link"/>
|
||||||
|
<child link="left_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="left_wrist_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0.100 0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="left_elbow_link"/>
|
||||||
|
<child link="left_wrist_roll_rubber_hand"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_wrist_roll_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.10794656650 0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||||
|
<mass value="0.35692864"/>
|
||||||
|
<inertia ixx="0.00019613494735" ixy="-0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="0.00000249774203" izz="0.00194181412808"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<link name="right_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 -0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="-2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 -0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.0039563 -0.10021 0.23778" rpy="-0.27931 5.4949E-05 0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="right_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 -0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 -0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.038 -0.013831" rpy="0.27925 0 0"/>
|
||||||
|
<parent link="right_shoulder_pitch_link"/>
|
||||||
|
<child link="right_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-2.2515" upper="1.5882" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="-7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_roll_link"/>
|
||||||
|
<child link="right_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 -0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="-6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_elbow_joint" type="revolute">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_yaw_link"/>
|
||||||
|
<child link="right_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="right_wrist_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0.100 -0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="right_elbow_link"/>
|
||||||
|
<child link="right_wrist_roll_rubber_hand"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_wrist_roll_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.10794656650 -0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||||
|
<mass value="0.35692864"/>
|
||||||
|
<inertia ixx="0.00019613494735" ixy="0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="-0.00000249774203" izz="0.00194181412808"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
249
resources/robots/g1_description/g1_23dof.xml
Normal file
249
resources/robots/g1_description/g1_23dof.xml
Normal file
@ -0,0 +1,249 @@
|
|||||||
|
<mujoco model="g1_23dof">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_rubber_hand" file="left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_rubber_hand" file="right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="torso_link" pos="-0.0039635 0 0.054">
|
||||||
|
<inertial pos="0.0034309 0.00025505 0.174524" quat="0.99988 0.000261157 0.0149809 -0.0038211" mass="9.842" diaginertia="0.135151 0.123088 0.0327256"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_rubber_hand" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.107947 0.00163512 0.00202245" quat="0.494051 0.504265 0.48416 0.516933" mass="0.356929" diaginertia="0.00200292 0.0019426 0.000195232"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_rubber_hand" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.107947 -0.00163512 0.00202245" quat="0.516933 0.48416 0.504265 0.494051" mass="0.356929" diaginertia="0.00200292 0.0019426 0.000195232"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
854
resources/robots/g1_description/g1_23dof_rev_1_0.urdf
Normal file
854
resources/robots/g1_description/g1_23dof_rev_1_0.urdf
Normal file
@ -0,0 +1,854 @@
|
|||||||
|
<robot name="g1_23dof_rev_1_0">
|
||||||
|
<mujoco>
|
||||||
|
<compiler meshdir="meshes" discardvisual="false"/>
|
||||||
|
</mujoco>
|
||||||
|
|
||||||
|
<!-- [CAUTION] uncomment when convert to mujoco -->
|
||||||
|
<!-- <link name="world"></link>
|
||||||
|
<joint name="floating_base_joint" type="floating">
|
||||||
|
<parent link="world"/>
|
||||||
|
<child link="pelvis"/>
|
||||||
|
</joint> -->
|
||||||
|
|
||||||
|
<link name="pelvis">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 -0.07605" rpy="0 0 0"/>
|
||||||
|
<mass value="3.813"/>
|
||||||
|
<inertia ixx="0.010549" ixy="0" ixz="2.1E-06" iyy="0.0093089" iyz="0" izz="0.0079184"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<link name="pelvis_contour_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="pelvis_contour_joint" type="fixed">
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="pelvis_contour_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Legs -->
|
||||||
|
<link name="left_hip_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002741 0.047791 -0.02606" rpy="0 0 0"/>
|
||||||
|
<mass value="1.35"/>
|
||||||
|
<inertia ixx="0.001811" ixy="3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="0.000171" izz="0.0012812"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.064452 -0.1027" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="left_hip_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_hip_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.029812 -0.001045 -0.087934" rpy="0 0 0"/>
|
||||||
|
<mass value="1.52"/>
|
||||||
|
<inertia ixx="0.0023773" ixy="-3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="1.84E-05" izz="0.0016595"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||||
|
<parent link="left_hip_pitch_link"/>
|
||||||
|
<child link="left_hip_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.5236" upper="2.9671" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_hip_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.057709 -0.010981 -0.15078" rpy="0 0 0"/>
|
||||||
|
<mass value="1.702"/>
|
||||||
|
<inertia ixx="0.0057774" ixy="-0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="-0.0007072" izz="0.003149"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hip_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||||
|
<parent link="left_hip_roll_link"/>
|
||||||
|
<child link="left_hip_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_knee_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005457 0.003964 -0.12074" rpy="0 0 0"/>
|
||||||
|
<mass value="1.932"/>
|
||||||
|
<inertia ixx="0.011329" ixy="4.82E-05" ixz="-4.49E-05" iyy="0.011277" iyz="-0.0007146" izz="0.0015168"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_knee_joint" type="revolute">
|
||||||
|
<origin xyz="-0.078273 0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||||
|
<parent link="left_hip_yaw_link"/>
|
||||||
|
<child link="left_knee_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_ankle_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||||
|
<mass value="0.074"/>
|
||||||
|
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_ankle_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 -9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||||
|
<parent link="left_knee_link"/>
|
||||||
|
<child link="left_ankle_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_ankle_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||||
|
<mass value="0.608"/>
|
||||||
|
<inertia ixx="0.0002231" ixy="2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="-1E-07" izz="0.0016667"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_ankle_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_ankle_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||||
|
<parent link="left_ankle_pitch_link"/>
|
||||||
|
<child link="left_ankle_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002741 -0.047791 -0.02606" rpy="0 0 0"/>
|
||||||
|
<mass value="1.35"/>
|
||||||
|
<inertia ixx="0.001811" ixy="-3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="-0.000171" izz="0.0012812"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.064452 -0.1027" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="right_hip_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.029812 0.001045 -0.087934" rpy="0 0 0"/>
|
||||||
|
<mass value="1.52"/>
|
||||||
|
<inertia ixx="0.0023773" ixy="3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="-1.84E-05" izz="0.0016595"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||||||
|
<parent link="right_hip_pitch_link"/>
|
||||||
|
<child link="right_hip_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-2.9671" upper="0.5236" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_hip_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.057709 0.010981 -0.15078" rpy="0 0 0"/>
|
||||||
|
<mass value="1.702"/>
|
||||||
|
<inertia ixx="0.0057774" ixy="0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="0.0007072" izz="0.003149"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hip_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||||||
|
<parent link="right_hip_roll_link"/>
|
||||||
|
<child link="right_hip_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_knee_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005457 -0.003964 -0.12074" rpy="0 0 0"/>
|
||||||
|
<mass value="1.932"/>
|
||||||
|
<inertia ixx="0.011329" ixy="-4.82E-05" ixz="4.49E-05" iyy="0.011277" iyz="0.0007146" izz="0.0015168"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_knee_joint" type="revolute">
|
||||||
|
<origin xyz="-0.078273 -0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||||||
|
<parent link="right_hip_yaw_link"/>
|
||||||
|
<child link="right_knee_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_ankle_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||||||
|
<mass value="0.074"/>
|
||||||
|
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_ankle_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0 9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||||||
|
<parent link="right_knee_link"/>
|
||||||
|
<child link="right_ankle_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_ankle_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||||||
|
<mass value="0.608"/>
|
||||||
|
<inertia ixx="0.0002231" ixy="-2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="1E-07" izz="0.0016667"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_ankle_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_ankle_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||||||
|
<parent link="right_ankle_pitch_link"/>
|
||||||
|
<child link="right_ankle_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Torso -->
|
||||||
|
<joint name="waist_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="-0.0039635 0 0.044" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="torso_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="88" velocity="32"/>
|
||||||
|
</joint>
|
||||||
|
<link name="torso_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.000931 0.000346 0.15082" rpy="0 0 0"/>
|
||||||
|
<mass value="6.78"/>
|
||||||
|
<inertia ixx="0.05905" ixy="3.3302E-05" ixz="-0.0017715" iyy="0.047014" iyz="-2.2399E-05" izz="0.025652"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link_23dof_rev_1_0.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link_23dof_rev_1_0.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- LOGO -->
|
||||||
|
<joint name="logo_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="logo_link"/>
|
||||||
|
</joint>
|
||||||
|
<link name="logo_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Head -->
|
||||||
|
<link name="head_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005267 0.000299 0.449869" rpy="0 0 0"/>
|
||||||
|
<mass value="1.036"/>
|
||||||
|
<inertia ixx="0.004085051" ixy="-2.543E-06" ixz="-6.9455E-05" iyy="0.004185212" iyz="-3.726E-06" izz="0.001807911"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="head_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.044" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="head_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- IMU -->
|
||||||
|
<link name="imu_in_torso"></link>
|
||||||
|
<joint name="imu_in_torso_joint" type="fixed">
|
||||||
|
<origin xyz="-0.03959 -0.00224 0.14792" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="imu_in_torso"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="imu_in_pelvis"></link>
|
||||||
|
<joint name="imu_in_pelvis_joint" type="fixed">
|
||||||
|
<origin xyz="0.04525 0 -0.08339" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="imu_in_pelvis"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- d435 -->
|
||||||
|
<link name="d435_link"></link>
|
||||||
|
<joint name="d435_joint" type="fixed">
|
||||||
|
<origin xyz="0.0576235 0.01753 0.42987" rpy="0 0.8307767239493009 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="d435_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- mid360 -->
|
||||||
|
<link name="mid360_link"></link>
|
||||||
|
<joint name="mid360_joint" type="fixed">
|
||||||
|
<origin xyz="0.0002835 0.00003 0.41618" rpy="0 0.04014257279586953 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="mid360_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Arm -->
|
||||||
|
<link name="left_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="-9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.0039563 0.10022 0.24778" rpy="0.27931 5.4949E-05 -0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="left_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="-1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="-5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.038 -0.013831" rpy="-0.27925 0 0"/>
|
||||||
|
<parent link="left_shoulder_pitch_link"/>
|
||||||
|
<child link="left_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-1.5882" upper="2.2515" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 -0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="-2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_roll_link"/>
|
||||||
|
<child link="left_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="-5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_elbow_joint" type="revolute">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_yaw_link"/>
|
||||||
|
<child link="left_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="left_wrist_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0.100 0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="left_elbow_link"/>
|
||||||
|
<child link="left_wrist_roll_rubber_hand"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_wrist_roll_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.10794656650 0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||||
|
<mass value="0.35692864"/>
|
||||||
|
<inertia ixx="0.00019613494735" ixy="-0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="0.00000249774203" izz="0.00194181412808"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<link name="right_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 -0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="-2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 -0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.0039563 -0.10021 0.24778" rpy="-0.27931 5.4949E-05 0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="right_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 -0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 -0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.038 -0.013831" rpy="0.27925 0 0"/>
|
||||||
|
<parent link="right_shoulder_pitch_link"/>
|
||||||
|
<child link="right_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-2.2515" upper="1.5882" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="-7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_roll_link"/>
|
||||||
|
<child link="right_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 -0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="-6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_elbow_joint" type="revolute">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_yaw_link"/>
|
||||||
|
<child link="right_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="right_wrist_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0.100 -0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="right_elbow_link"/>
|
||||||
|
<child link="right_wrist_roll_rubber_hand"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_wrist_roll_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.10794656650 -0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||||||
|
<mass value="0.35692864"/>
|
||||||
|
<inertia ixx="0.00019613494735" ixy="0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="-0.00000249774203" izz="0.00194181412808"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
244
resources/robots/g1_description/g1_23dof_rev_1_0.xml
Normal file
244
resources/robots/g1_description/g1_23dof_rev_1_0.xml
Normal file
@ -0,0 +1,244 @@
|
|||||||
|
<mujoco model="g1_23dof_rev_1_0">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="torso_link_23dof_rev_1_0" file="torso_link_23dof_rev_1_0.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_rubber_hand" file="left_wrist_roll_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_rubber_hand" file="right_wrist_roll_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="torso_link" pos="-0.0039635 0 0.044">
|
||||||
|
<inertial pos="0.00203158 0.000339683 0.184568" quat="0.999803 -6.03319e-05 0.0198256 0.00131986" mass="7.818" diaginertia="0.121847 0.109825 0.0273735"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link_23dof_rev_1_0"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link_23dof_rev_1_0"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.24778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_rubber_hand" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.107947 0.00163512 0.00202245" quat="0.494051 0.504265 0.48416 0.516933" mass="0.356929" diaginertia="0.00200292 0.0019426 0.000195232"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.24778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_rubber_hand" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.107947 -0.00163512 0.00202245" quat="0.516933 0.48416 0.504265 0.494051" mass="0.356929" diaginertia="0.00200292 0.0019426 0.000195232"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
1086
resources/robots/g1_description/g1_29dof.urdf
Normal file
1086
resources/robots/g1_description/g1_29dof.urdf
Normal file
File diff suppressed because it is too large
Load Diff
297
resources/robots/g1_description/g1_29dof.xml
Normal file
297
resources/robots/g1_description/g1_29dof.xml
Normal file
@ -0,0 +1,297 @@
|
|||||||
|
<mujoco model="g1_29dof">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||||
|
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="left_rubber_hand" file="left_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="right_rubber_hand" file="right_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="waist_yaw_link">
|
||||||
|
<inertial pos="0.003964 0 0.018769" quat="-0.0178291 0.628464 0.0282471 0.777121" mass="0.244" diaginertia="0.000158561 0.000124229 9.67669e-05"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<body name="waist_roll_link" pos="-0.0039635 0 0.035">
|
||||||
|
<inertial pos="0 -0.000236 0.010111" quat="0.99979 0.020492 0 0" mass="0.047" diaginertia="7.515e-06 6.40206e-06 3.98394e-06"/>
|
||||||
|
<joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||||
|
<body name="torso_link" pos="0 0 0.019">
|
||||||
|
<inertial pos="0.00331658 0.000261533 0.179856" quat="0.999831 0.000376204 0.0179895 -0.00377704" mass="9.598" diaginertia="0.12407 0.111951 0.0325382"/>
|
||||||
|
<joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="waist_roll_joint" joint="waist_roll_joint"/>
|
||||||
|
<motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
1086
resources/robots/g1_description/g1_29dof_lock_waist.urdf
Normal file
1086
resources/robots/g1_description/g1_29dof_lock_waist.urdf
Normal file
File diff suppressed because it is too large
Load Diff
293
resources/robots/g1_description/g1_29dof_lock_waist.xml
Normal file
293
resources/robots/g1_description/g1_29dof_lock_waist.xml
Normal file
@ -0,0 +1,293 @@
|
|||||||
|
<mujoco model="g1_29dof_lock_waist">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||||
|
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="left_rubber_hand" file="left_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="right_rubber_hand" file="right_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="waist_yaw_link">
|
||||||
|
<inertial pos="0.003964 0 0.018769" quat="-0.0178291 0.628464 0.0282471 0.777121" mass="0.244" diaginertia="0.000158561 0.000124229 9.67669e-05"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<body name="waist_roll_link" pos="-0.0039635 0 0.035">
|
||||||
|
<inertial pos="0 -0.000236 0.010111" quat="0.99979 0.020492 0 0" mass="0.047" diaginertia="7.515e-06 6.40206e-06 3.98394e-06"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||||
|
<body name="torso_link" pos="0 0 0.019">
|
||||||
|
<inertial pos="0.00331658 0.000261533 0.179856" quat="0.999831 0.000376204 0.0179895 -0.00377704" mass="9.598" diaginertia="0.12407 0.111951 0.0325382"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
1058
resources/robots/g1_description/g1_29dof_lock_waist_rev_1_0.urdf
Normal file
1058
resources/robots/g1_description/g1_29dof_lock_waist_rev_1_0.urdf
Normal file
File diff suppressed because it is too large
Load Diff
290
resources/robots/g1_description/g1_29dof_lock_waist_rev_1_0.xml
Normal file
290
resources/robots/g1_description/g1_29dof_lock_waist_rev_1_0.xml
Normal file
@ -0,0 +1,290 @@
|
|||||||
|
<mujoco model="g1_29dof_lock_waist_rev_1_0">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="waist_roll_link" file="waist_roll_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="left_rubber_hand" file="left_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="right_rubber_hand" file="right_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="waist_yaw_link">
|
||||||
|
<inertial pos="0.003494 0.000233 0.018034" quat="0.289697 0.591001 -0.337795 0.672821" mass="0.214" diaginertia="0.000163531 0.000107714 0.000102205"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<body name="waist_roll_link" pos="-0.0039635 0 0.044">
|
||||||
|
<inertial pos="0 2.3e-05 0" quat="0.5 0.5 -0.5 0.5" mass="0.086" diaginertia="8.245e-06 7.079e-06 6.339e-06"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||||
|
<body name="torso_link">
|
||||||
|
<inertial pos="0.00203158 0.000339683 0.184568" quat="0.999803 -6.03319e-05 0.0198256 0.00131986" mass="7.818" diaginertia="0.121847 0.109825 0.0273735"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.24778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.24778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
1058
resources/robots/g1_description/g1_29dof_rev_1_0.urdf
Normal file
1058
resources/robots/g1_description/g1_29dof_rev_1_0.urdf
Normal file
File diff suppressed because it is too large
Load Diff
294
resources/robots/g1_description/g1_29dof_rev_1_0.xml
Normal file
294
resources/robots/g1_description/g1_29dof_rev_1_0.xml
Normal file
@ -0,0 +1,294 @@
|
|||||||
|
<mujoco model="g1_29dof_rev_1_0">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="waist_roll_link" file="waist_roll_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="left_rubber_hand" file="left_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="right_rubber_hand" file="right_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="waist_yaw_link">
|
||||||
|
<inertial pos="0.003494 0.000233 0.018034" quat="0.289697 0.591001 -0.337795 0.672821" mass="0.214" diaginertia="0.000163531 0.000107714 0.000102205"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<body name="waist_roll_link" pos="-0.0039635 0 0.044">
|
||||||
|
<inertial pos="0 2.3e-05 0" quat="0.5 0.5 -0.5 0.5" mass="0.086" diaginertia="8.245e-06 7.079e-06 6.339e-06"/>
|
||||||
|
<joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||||
|
<body name="torso_link">
|
||||||
|
<inertial pos="0.00203158 0.000339683 0.184568" quat="0.999803 -6.03319e-05 0.0198256 0.00131986" mass="7.818" diaginertia="0.121847 0.109825 0.0273735"/>
|
||||||
|
<joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.24778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.24778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="waist_roll_joint" joint="waist_roll_joint"/>
|
||||||
|
<motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
1504
resources/robots/g1_description/g1_29dof_with_hand.urdf
Normal file
1504
resources/robots/g1_description/g1_29dof_with_hand.urdf
Normal file
File diff suppressed because it is too large
Load Diff
411
resources/robots/g1_description/g1_29dof_with_hand.xml
Normal file
411
resources/robots/g1_description/g1_29dof_with_hand.xml
Normal file
@ -0,0 +1,411 @@
|
|||||||
|
<mujoco model="g1_29dof_with_hand">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||||
|
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="left_hand_palm_link" file="left_hand_palm_link.STL"/>
|
||||||
|
<mesh name="left_hand_thumb_0_link" file="left_hand_thumb_0_link.STL"/>
|
||||||
|
<mesh name="left_hand_thumb_1_link" file="left_hand_thumb_1_link.STL"/>
|
||||||
|
<mesh name="left_hand_thumb_2_link" file="left_hand_thumb_2_link.STL"/>
|
||||||
|
<mesh name="left_hand_middle_0_link" file="left_hand_middle_0_link.STL"/>
|
||||||
|
<mesh name="left_hand_middle_1_link" file="left_hand_middle_1_link.STL"/>
|
||||||
|
<mesh name="left_hand_index_0_link" file="left_hand_index_0_link.STL"/>
|
||||||
|
<mesh name="left_hand_index_1_link" file="left_hand_index_1_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="right_hand_palm_link" file="right_hand_palm_link.STL"/>
|
||||||
|
<mesh name="right_hand_thumb_0_link" file="right_hand_thumb_0_link.STL"/>
|
||||||
|
<mesh name="right_hand_thumb_1_link" file="right_hand_thumb_1_link.STL"/>
|
||||||
|
<mesh name="right_hand_thumb_2_link" file="right_hand_thumb_2_link.STL"/>
|
||||||
|
<mesh name="right_hand_middle_0_link" file="right_hand_middle_0_link.STL"/>
|
||||||
|
<mesh name="right_hand_middle_1_link" file="right_hand_middle_1_link.STL"/>
|
||||||
|
<mesh name="right_hand_index_0_link" file="right_hand_index_0_link.STL"/>
|
||||||
|
<mesh name="right_hand_index_1_link" file="right_hand_index_1_link.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="waist_yaw_link">
|
||||||
|
<inertial pos="0.003964 0 0.018769" quat="-0.0178291 0.628464 0.0282471 0.777121" mass="0.244" diaginertia="0.000158561 0.000124229 9.67669e-05"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<body name="waist_roll_link" pos="-0.0039635 0 0.035">
|
||||||
|
<inertial pos="0 -0.000236 0.010111" quat="0.99979 0.020492 0 0" mass="0.047" diaginertia="7.515e-06 6.40206e-06 3.98394e-06"/>
|
||||||
|
<joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||||
|
<body name="torso_link" pos="0 0 0.019">
|
||||||
|
<inertial pos="0.00331658 0.000261533 0.179856" quat="0.999831 0.000376204 0.0179895 -0.00377704" mass="9.598" diaginertia="0.12407 0.111951 0.0325382"/>
|
||||||
|
<joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.054" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.23778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0885506 0.00212216 -0.000374562" quat="0.487149 0.493844 0.513241 0.505358" mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
|
||||||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
|
||||||
|
<body name="left_hand_thumb_0_link" pos="0.067 0.003 0">
|
||||||
|
<inertial pos="-0.000884246 -0.00863407 0.000944293" quat="0.462991 0.643965 -0.460173 0.398986" mass="0.0862366" diaginertia="1.6546e-05 1.60058e-05 1.43741e-05"/>
|
||||||
|
<joint name="left_hand_thumb_0_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_0_link"/>
|
||||||
|
<body name="left_hand_thumb_1_link" pos="-0.0025 -0.0193 0">
|
||||||
|
<inertial pos="-0.000827888 -0.0354744 -0.0003809" quat="0.685598 0.705471 -0.15207 0.0956069" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="left_hand_thumb_1_joint" pos="0 0 0" axis="0 0 1" range="-0.724312 1.0472" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_1_link"/>
|
||||||
|
<geom size="0.01 0.015 0.01" pos="-0.001 -0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_hand_thumb_2_link" pos="0 -0.0458 0">
|
||||||
|
<inertial pos="-0.00171735 -0.0262819 0.000107789" quat="0.703174 0.710977 -0.00017564 -0.00766553" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="left_hand_thumb_2_joint" pos="0 0 0" axis="0 0 1" range="0 1.74533" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_2_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_2_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="left_hand_middle_0_link" pos="0.1192 0.0046 -0.0285">
|
||||||
|
<inertial pos="0.0354744 0.000827888 0.0003809" quat="0.391313 0.552395 0.417187 0.606373" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="left_hand_middle_0_joint" pos="0 0 0" axis="0 0 1" range="-1.5708 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_0_link"/>
|
||||||
|
<body name="left_hand_middle_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 0.00171735 -0.000107789" quat="0.502612 0.491799 0.502639 0.502861" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="left_hand_middle_1_joint" pos="0 0 0" axis="0 0 1" range="-1.74533 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="left_hand_index_0_link" pos="0.1192 0.0046 0.0285">
|
||||||
|
<inertial pos="0.0354744 0.000827888 0.0003809" quat="0.391313 0.552395 0.417187 0.606373" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="left_hand_index_0_joint" pos="0 0 0" axis="0 0 1" range="-1.5708 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_0_link"/>
|
||||||
|
<body name="left_hand_index_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 0.00171735 -0.000107789" quat="0.502612 0.491799 0.502639 0.502861" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="left_hand_index_1_joint" pos="0 0 0" axis="0 0 1" range="-1.74533 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.23778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0885506 -0.00212216 -0.000374562" quat="0.505358 0.513241 0.493844 0.487149" mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
|
||||||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
|
||||||
|
<body name="right_hand_thumb_0_link" pos="0.067 -0.003 0">
|
||||||
|
<inertial pos="-0.000884246 0.00863407 0.000944293" quat="0.643965 0.462991 -0.398986 0.460173" mass="0.0862366" diaginertia="1.6546e-05 1.60058e-05 1.43741e-05"/>
|
||||||
|
<joint name="right_hand_thumb_0_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_0_link"/>
|
||||||
|
<body name="right_hand_thumb_1_link" pos="-0.0025 0.0193 0">
|
||||||
|
<inertial pos="-0.000827888 0.0354744 -0.0003809" quat="0.705471 0.685598 -0.0956069 0.15207" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="right_hand_thumb_1_joint" pos="0 0 0" axis="0 0 1" range="-1.0472 0.724312" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_1_link"/>
|
||||||
|
<geom size="0.01 0.015 0.01" pos="-0.001 0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_hand_thumb_2_link" pos="0 0.0458 0">
|
||||||
|
<inertial pos="-0.00171735 0.0262819 0.000107789" quat="0.710977 0.703174 0.00766553 0.00017564" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="right_hand_thumb_2_joint" pos="0 0 0" axis="0 0 1" range="-1.74533 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_2_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_2_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hand_middle_0_link" pos="0.1192 -0.0046 -0.0285">
|
||||||
|
<inertial pos="0.0354744 -0.000827888 0.0003809" quat="0.606373 0.417187 0.552395 0.391313" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="right_hand_middle_0_joint" pos="0 0 0" axis="0 0 1" range="0 1.5708" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_0_link"/>
|
||||||
|
<body name="right_hand_middle_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 -0.00171735 -0.000107789" quat="0.502861 0.502639 0.491799 0.502612" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="right_hand_middle_1_joint" pos="0 0 0" axis="0 0 1" range="0 1.74533" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hand_index_0_link" pos="0.1192 -0.0046 0.0285">
|
||||||
|
<inertial pos="0.0354744 -0.000827888 0.0003809" quat="0.606373 0.417187 0.552395 0.391313" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="right_hand_index_0_joint" pos="0 0 0" axis="0 0 1" range="0 1.5708" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_0_link"/>
|
||||||
|
<body name="right_hand_index_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 -0.00171735 -0.000107789" quat="0.502861 0.502639 0.491799 0.502612" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="right_hand_index_1_joint" pos="0 0 0" axis="0 0 1" range="0 1.74533" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="waist_roll_joint" joint="waist_roll_joint"/>
|
||||||
|
<motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||||
|
<motor name="left_hand_thumb_0_joint" joint="left_hand_thumb_0_joint"/>
|
||||||
|
<motor name="left_hand_thumb_1_joint" joint="left_hand_thumb_1_joint"/>
|
||||||
|
<motor name="left_hand_thumb_2_joint" joint="left_hand_thumb_2_joint"/>
|
||||||
|
<motor name="left_hand_middle_0_joint" joint="left_hand_middle_0_joint"/>
|
||||||
|
<motor name="left_hand_middle_1_joint" joint="left_hand_middle_1_joint"/>
|
||||||
|
<motor name="left_hand_index_0_joint" joint="left_hand_index_0_joint"/>
|
||||||
|
<motor name="left_hand_index_1_joint" joint="left_hand_index_1_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||||
|
<motor name="right_hand_thumb_0_joint" joint="right_hand_thumb_0_joint"/>
|
||||||
|
<motor name="right_hand_thumb_1_joint" joint="right_hand_thumb_1_joint"/>
|
||||||
|
<motor name="right_hand_thumb_2_joint" joint="right_hand_thumb_2_joint"/>
|
||||||
|
<motor name="right_hand_index_0_joint" joint="right_hand_index_0_joint"/>
|
||||||
|
<motor name="right_hand_index_1_joint" joint="right_hand_index_1_joint"/>
|
||||||
|
<motor name="right_hand_middle_0_joint" joint="right_hand_middle_0_joint"/>
|
||||||
|
<motor name="right_hand_middle_1_joint" joint="right_hand_middle_1_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
1476
resources/robots/g1_description/g1_29dof_with_hand_rev_1_0.urdf
Normal file
1476
resources/robots/g1_description/g1_29dof_with_hand_rev_1_0.urdf
Normal file
File diff suppressed because it is too large
Load Diff
408
resources/robots/g1_description/g1_29dof_with_hand_rev_1_0.xml
Normal file
408
resources/robots/g1_description/g1_29dof_with_hand_rev_1_0.xml
Normal file
@ -0,0 +1,408 @@
|
|||||||
|
<mujoco model="g1_29dof_with_hand_rev_1_0">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||||||
|
<mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
|
||||||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||||||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||||||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||||||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||||||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||||||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||||||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||||||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="waist_roll_link" file="waist_roll_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link_rev_1_0.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="left_hand_palm_link" file="left_hand_palm_link.STL"/>
|
||||||
|
<mesh name="left_hand_thumb_0_link" file="left_hand_thumb_0_link.STL"/>
|
||||||
|
<mesh name="left_hand_thumb_1_link" file="left_hand_thumb_1_link.STL"/>
|
||||||
|
<mesh name="left_hand_thumb_2_link" file="left_hand_thumb_2_link.STL"/>
|
||||||
|
<mesh name="left_hand_middle_0_link" file="left_hand_middle_0_link.STL"/>
|
||||||
|
<mesh name="left_hand_middle_1_link" file="left_hand_middle_1_link.STL"/>
|
||||||
|
<mesh name="left_hand_index_0_link" file="left_hand_index_0_link.STL"/>
|
||||||
|
<mesh name="left_hand_index_1_link" file="left_hand_index_1_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="right_hand_palm_link" file="right_hand_palm_link.STL"/>
|
||||||
|
<mesh name="right_hand_thumb_0_link" file="right_hand_thumb_0_link.STL"/>
|
||||||
|
<mesh name="right_hand_thumb_1_link" file="right_hand_thumb_1_link.STL"/>
|
||||||
|
<mesh name="right_hand_thumb_2_link" file="right_hand_thumb_2_link.STL"/>
|
||||||
|
<mesh name="right_hand_middle_0_link" file="right_hand_middle_0_link.STL"/>
|
||||||
|
<mesh name="right_hand_middle_1_link" file="right_hand_middle_1_link.STL"/>
|
||||||
|
<mesh name="right_hand_index_0_link" file="right_hand_index_0_link.STL"/>
|
||||||
|
<mesh name="right_hand_index_1_link" file="right_hand_index_1_link.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<body name="pelvis" pos="0 0 0.793">
|
||||||
|
<inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
|
||||||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
|
||||||
|
<site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
|
||||||
|
<body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
|
||||||
|
<body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
|
||||||
|
<body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
|
||||||
|
<body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
|
||||||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
|
||||||
|
<body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
|
||||||
|
<body name="left_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
|
||||||
|
<inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
|
||||||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
|
||||||
|
<body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
|
||||||
|
<inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
|
||||||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
|
||||||
|
<body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
|
||||||
|
<inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
|
||||||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
|
||||||
|
<body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
|
||||||
|
<inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
|
||||||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
|
||||||
|
<body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
|
||||||
|
<inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
|
||||||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
|
||||||
|
<body name="right_ankle_roll_link" pos="0 0 -0.017558">
|
||||||
|
<inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
|
||||||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
|
||||||
|
<geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
<geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="waist_yaw_link">
|
||||||
|
<inertial pos="0.003494 0.000233 0.018034" quat="0.289697 0.591001 -0.337795 0.672821" mass="0.214" diaginertia="0.000163531 0.000107714 0.000102205"/>
|
||||||
|
<joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<body name="waist_roll_link" pos="-0.0039635 0 0.044">
|
||||||
|
<inertial pos="0 2.3e-05 0" quat="0.5 0.5 -0.5 0.5" mass="0.086" diaginertia="8.245e-06 7.079e-06 6.339e-06"/>
|
||||||
|
<joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||||
|
<body name="torso_link">
|
||||||
|
<inertial pos="0.00203158 0.000339683 0.184568" quat="0.999803 -6.03319e-05 0.0198256 0.00131986" mass="7.818" diaginertia="0.121847 0.109825 0.0273735"/>
|
||||||
|
<joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom pos="0.0039635 0 -0.044" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.24778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0885506 0.00212216 -0.000374562" quat="0.487149 0.493844 0.513241 0.505358" mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
|
||||||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_palm_link"/>
|
||||||
|
<body name="left_hand_thumb_0_link" pos="0.067 0.003 0">
|
||||||
|
<inertial pos="-0.000884246 -0.00863407 0.000944293" quat="0.462991 0.643965 -0.460173 0.398986" mass="0.0862366" diaginertia="1.6546e-05 1.60058e-05 1.43741e-05"/>
|
||||||
|
<joint name="left_hand_thumb_0_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_0_link"/>
|
||||||
|
<body name="left_hand_thumb_1_link" pos="-0.0025 -0.0193 0">
|
||||||
|
<inertial pos="-0.000827888 -0.0354744 -0.0003809" quat="0.685598 0.705471 -0.15207 0.0956069" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="left_hand_thumb_1_joint" pos="0 0 0" axis="0 0 1" range="-0.724312 1.0472" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_1_link"/>
|
||||||
|
<geom size="0.01 0.015 0.01" pos="-0.001 -0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_hand_thumb_2_link" pos="0 -0.0458 0">
|
||||||
|
<inertial pos="-0.00171735 -0.0262819 0.000107789" quat="0.703174 0.710977 -0.00017564 -0.00766553" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="left_hand_thumb_2_joint" pos="0 0 0" axis="0 0 1" range="0 1.74533" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_2_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_thumb_2_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="left_hand_middle_0_link" pos="0.1192 0.0046 -0.0285">
|
||||||
|
<inertial pos="0.0354744 0.000827888 0.0003809" quat="0.391313 0.552395 0.417187 0.606373" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="left_hand_middle_0_joint" pos="0 0 0" axis="0 0 1" range="-1.5708 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_0_link"/>
|
||||||
|
<body name="left_hand_middle_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 0.00171735 -0.000107789" quat="0.502612 0.491799 0.502639 0.502861" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="left_hand_middle_1_joint" pos="0 0 0" axis="0 0 1" range="-1.74533 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_middle_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="left_hand_index_0_link" pos="0.1192 0.0046 0.0285">
|
||||||
|
<inertial pos="0.0354744 0.000827888 0.0003809" quat="0.391313 0.552395 0.417187 0.606373" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="left_hand_index_0_joint" pos="0 0 0" axis="0 0 1" range="-1.5708 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_0_link"/>
|
||||||
|
<body name="left_hand_index_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 0.00171735 -0.000107789" quat="0.502612 0.491799 0.502639 0.502861" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="left_hand_index_1_joint" pos="0 0 0" axis="0 0 1" range="-1.74533 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hand_index_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.24778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0885506 -0.00212216 -0.000374562" quat="0.505358 0.513241 0.493844 0.487149" mass="0.457415" diaginertia="0.00105989 0.000895419 0.000323842"/>
|
||||||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_palm_link"/>
|
||||||
|
<body name="right_hand_thumb_0_link" pos="0.067 -0.003 0">
|
||||||
|
<inertial pos="-0.000884246 0.00863407 0.000944293" quat="0.643965 0.462991 -0.398986 0.460173" mass="0.0862366" diaginertia="1.6546e-05 1.60058e-05 1.43741e-05"/>
|
||||||
|
<joint name="right_hand_thumb_0_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 1.0472" actuatorfrcrange="-2.45 2.45"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_0_link"/>
|
||||||
|
<body name="right_hand_thumb_1_link" pos="-0.0025 0.0193 0">
|
||||||
|
<inertial pos="-0.000827888 0.0354744 -0.0003809" quat="0.705471 0.685598 -0.0956069 0.15207" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="right_hand_thumb_1_joint" pos="0 0 0" axis="0 0 1" range="-1.0472 0.724312" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_1_link"/>
|
||||||
|
<geom size="0.01 0.015 0.01" pos="-0.001 0.032 0" type="box" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_hand_thumb_2_link" pos="0 0.0458 0">
|
||||||
|
<inertial pos="-0.00171735 0.0262819 0.000107789" quat="0.710977 0.703174 0.00766553 0.00017564" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="right_hand_thumb_2_joint" pos="0 0 0" axis="0 0 1" range="-1.74533 0" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_2_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_thumb_2_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hand_middle_0_link" pos="0.1192 -0.0046 -0.0285">
|
||||||
|
<inertial pos="0.0354744 -0.000827888 0.0003809" quat="0.606373 0.417187 0.552395 0.391313" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="right_hand_middle_0_joint" pos="0 0 0" axis="0 0 1" range="0 1.5708" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_0_link"/>
|
||||||
|
<body name="right_hand_middle_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 -0.00171735 -0.000107789" quat="0.502861 0.502639 0.491799 0.502612" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="right_hand_middle_1_joint" pos="0 0 0" axis="0 0 1" range="0 1.74533" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_middle_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_hand_index_0_link" pos="0.1192 -0.0046 0.0285">
|
||||||
|
<inertial pos="0.0354744 -0.000827888 0.0003809" quat="0.606373 0.417187 0.552395 0.391313" mass="0.0588507" diaginertia="1.28514e-05 1.22902e-05 5.9666e-06"/>
|
||||||
|
<joint name="right_hand_index_0_joint" pos="0 0 0" axis="0 0 1" range="0 1.5708" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_0_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_0_link"/>
|
||||||
|
<body name="right_hand_index_1_link" pos="0.0458 0 0">
|
||||||
|
<inertial pos="0.0262819 -0.00171735 -0.000107789" quat="0.502861 0.502639 0.491799 0.502612" mass="0.0203063" diaginertia="4.61314e-06 3.86645e-06 1.53495e-06"/>
|
||||||
|
<joint name="right_hand_index_1_joint" pos="0 0 0" axis="0 0 1" range="0 1.74533" actuatorfrcrange="-1.4 1.4"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_1_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hand_index_1_link"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||||||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||||||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||||||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||||||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||||||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||||||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||||||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||||||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||||||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||||||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||||||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||||||
|
<motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
|
||||||
|
<motor name="waist_roll_joint" joint="waist_roll_joint"/>
|
||||||
|
<motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||||
|
<motor name="left_hand_thumb_0_joint" joint="left_hand_thumb_0_joint"/>
|
||||||
|
<motor name="left_hand_thumb_1_joint" joint="left_hand_thumb_1_joint"/>
|
||||||
|
<motor name="left_hand_thumb_2_joint" joint="left_hand_thumb_2_joint"/>
|
||||||
|
<motor name="left_hand_middle_0_joint" joint="left_hand_middle_0_joint"/>
|
||||||
|
<motor name="left_hand_middle_1_joint" joint="left_hand_middle_1_joint"/>
|
||||||
|
<motor name="left_hand_index_0_joint" joint="left_hand_index_0_joint"/>
|
||||||
|
<motor name="left_hand_index_1_joint" joint="left_hand_index_1_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||||
|
<motor name="right_hand_thumb_0_joint" joint="right_hand_thumb_0_joint"/>
|
||||||
|
<motor name="right_hand_thumb_1_joint" joint="right_hand_thumb_1_joint"/>
|
||||||
|
<motor name="right_hand_thumb_2_joint" joint="right_hand_thumb_2_joint"/>
|
||||||
|
<motor name="right_hand_index_0_joint" joint="right_hand_index_0_joint"/>
|
||||||
|
<motor name="right_hand_index_1_joint" joint="right_hand_index_1_joint"/>
|
||||||
|
<motor name="right_hand_middle_0_joint" joint="right_hand_middle_0_joint"/>
|
||||||
|
<motor name="right_hand_middle_1_joint" joint="right_hand_middle_1_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
<sensor>
|
||||||
|
<gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
|
||||||
|
<gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
|
||||||
|
<accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
650
resources/robots/g1_description/g1_dual_arm.urdf
Normal file
650
resources/robots/g1_description/g1_dual_arm.urdf
Normal file
@ -0,0 +1,650 @@
|
|||||||
|
<robot name="g1_dual_arm">
|
||||||
|
<mujoco>
|
||||||
|
<compiler meshdir="meshes" discardvisual="false"/>
|
||||||
|
</mujoco>
|
||||||
|
|
||||||
|
<!-- [CAUTION] uncomment when convert to mujoco -->
|
||||||
|
<!-- <link name="world"></link>
|
||||||
|
<joint name="floating_base_joint" type="floating">
|
||||||
|
<parent link="world"/>
|
||||||
|
<child link="waist_yaw_link"/>
|
||||||
|
</joint> -->
|
||||||
|
|
||||||
|
<!-- Torso -->
|
||||||
|
<link name="waist_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.003964 0 0.018769" rpy="0 0 0"/>
|
||||||
|
<mass value="0.244"/>
|
||||||
|
<inertia ixx="9.9587E-05" ixy="-1.833E-06" ixz="-1.2617E-05" iyy="0.00012411" iyz="-1.18E-07" izz="0.00015586"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/waist_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<link name="waist_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 -0.000236 0.010111" rpy="0 0 0"/>
|
||||||
|
<mass value="0.047"/>
|
||||||
|
<inertia ixx="7.515E-06" ixy="0" ixz="0" iyy="6.398E-06" iyz="9.9E-08" izz="3.988E-06"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/waist_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<joint name="waist_roll_joint" type="fixed">
|
||||||
|
<origin xyz="-0.0039635 0 0.035" rpy="0 0 0"/>
|
||||||
|
<parent link="waist_yaw_link"/>
|
||||||
|
<child link="waist_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-0.52" upper="0.52" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="torso_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.002601 0.000257 0.153719" rpy="0 0 0"/>
|
||||||
|
<mass value="8.562"/>
|
||||||
|
<inertia ixx="0.065674966" ixy="-8.597E-05" ixz="-0.001737252" iyy="0.053535188" iyz="8.6899E-05" izz="0.030808125"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/torso_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="waist_pitch_joint" type="fixed">
|
||||||
|
<origin xyz="0 0 0.019" rpy="0 0 0"/>
|
||||||
|
<parent link="waist_roll_link"/>
|
||||||
|
<child link="torso_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-0.52" upper="0.52" effort="50" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- LOGO -->
|
||||||
|
<joint name="logo_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="logo_link"/>
|
||||||
|
</joint>
|
||||||
|
<link name="logo_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/logo_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- Head -->
|
||||||
|
<link name="head_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.005267 0.000299 0.449869" rpy="0 0 0"/>
|
||||||
|
<mass value="1.036"/>
|
||||||
|
<inertia ixx="0.004085051" ixy="-2.543E-06" ixz="-6.9455E-05" iyy="0.004185212" iyz="-3.726E-06" izz="0.001807911"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="dark">
|
||||||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/head_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="head_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="head_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Waist Support -->
|
||||||
|
<link name="waist_support_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<mass value="0.001"/>
|
||||||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/waist_support_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/waist_support_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="waist_support_joint" type="fixed">
|
||||||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="waist_support_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- IMU -->
|
||||||
|
<link name="imu_in_torso"></link>
|
||||||
|
<joint name="imu_in_torso_joint" type="fixed">
|
||||||
|
<origin xyz="-0.03959 -0.00224 0.13792" rpy="0 0 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="imu_in_torso"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="imu_in_pelvis"></link>
|
||||||
|
<joint name="imu_in_pelvis_joint" type="fixed">
|
||||||
|
<origin xyz="0.04525 0 -0.08339" rpy="0 0 0"/>
|
||||||
|
<parent link="pelvis"/>
|
||||||
|
<child link="imu_in_pelvis"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- d435 -->
|
||||||
|
<link name="d435_link"></link>
|
||||||
|
<joint name="d435_joint" type="fixed">
|
||||||
|
<origin xyz="0.0576235 0.01753 0.41987" rpy="0 0.8307767239493009 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="d435_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- mid360 -->
|
||||||
|
<link name="mid360_link"></link>
|
||||||
|
<joint name="mid360_joint" type="fixed">
|
||||||
|
<origin xyz="0.0002835 0.00003 0.40618" rpy="0 0.04014257279586953 0"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="mid360_link"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<!-- Arm -->
|
||||||
|
<link name="left_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="-9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.0039563 0.10022 0.23778" rpy="0.27931 5.4949E-05 -0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="left_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="-1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="-5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.038 -0.013831" rpy="-0.27925 0 0"/>
|
||||||
|
<parent link="left_shoulder_pitch_link"/>
|
||||||
|
<child link="left_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-1.5882" upper="2.2515" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 -0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="-2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_shoulder_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0 0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_roll_link"/>
|
||||||
|
<child link="left_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="-5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_elbow_joint" type="revolute">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="left_shoulder_yaw_link"/>
|
||||||
|
<child link="left_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="left_wrist_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0.100 0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="left_elbow_link"/>
|
||||||
|
<child link="left_wrist_roll_link"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_wrist_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.01713944778 0.00053759094 0.00000048864" rpy="0 0 0"/>
|
||||||
|
<mass value="0.08544498"/>
|
||||||
|
<inertia ixx="0.00004821544023" ixy="-0.00000424511021" ixz="0.00000000510599" iyy="0.00003722899093" iyz="-0.00000000123525" izz="0.00005482106541"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_wrist_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.038 0 0" rpy="0 0 0"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<parent link="left_wrist_roll_link"/>
|
||||||
|
<child link="left_wrist_pitch_link"/>
|
||||||
|
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_wrist_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.02299989837 -0.00111685314 -0.00111658096" rpy="0 0 0"/>
|
||||||
|
<mass value="0.48404956"/>
|
||||||
|
<inertia ixx="0.00016579646273" ixy="-0.00001231206746" ixz="0.00001231699194" iyy="0.00042954057410" iyz="0.00000081417712" izz="0.00042953697654"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_wrist_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.046 0 0" rpy="0 0 0"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<parent link="left_wrist_pitch_link"/>
|
||||||
|
<child link="left_wrist_yaw_link"/>
|
||||||
|
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_wrist_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.02200381568 0.00049485096 0.00053861123" rpy="0 0 0"/>
|
||||||
|
<mass value="0.08457647"/>
|
||||||
|
<inertia ixx="0.00004929128828" ixy="-0.00000045735494" ixz="0.00000445867591" iyy="0.00005973338134" iyz="0.00000043217198" izz="0.00003928083826"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_wrist_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="left_hand_palm_joint" type="fixed">
|
||||||
|
<origin xyz="0.0415 0.003 0" rpy="0 0 0"/>
|
||||||
|
<parent link="left_wrist_yaw_link"/>
|
||||||
|
<child link="left_rubber_hand"/>
|
||||||
|
</joint>
|
||||||
|
<link name="left_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.05361310808 -0.00295905240 0.00215413091" rpy="0 0 0"/>
|
||||||
|
<mass value="0.170"/>
|
||||||
|
<inertia ixx="0.00010099485234748" ixy="0.00003618590790516" ixz="-0.00000074301518642" iyy="0.00028135871571621" iyz="0.00000330189743286" izz="0.00021894770413514"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/left_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
<link name="right_shoulder_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 -0.035892 -0.011628" rpy="0 0 0"/>
|
||||||
|
<mass value="0.718"/>
|
||||||
|
<inertia ixx="0.0004291" ixy="9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="-2.26E-05" izz="0.000423"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 -0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.0039563 -0.10021 0.23778" rpy="-0.27931 5.4949E-05 0.00019159"/>
|
||||||
|
<parent link="torso_link"/>
|
||||||
|
<child link="right_shoulder_pitch_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="-0.000227 -0.00727 -0.063243" rpy="0 0 0"/>
|
||||||
|
<mass value="0.643"/>
|
||||||
|
<inertia ixx="0.0006177" ixy="1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="5.3E-06" izz="0.0003894"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="-0.004 -0.006 -0.053" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.03" length="0.03"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.038 -0.013831" rpy="0.27925 0 0"/>
|
||||||
|
<parent link="right_shoulder_pitch_link"/>
|
||||||
|
<child link="right_shoulder_roll_link"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<limit lower="-2.2515" upper="1.5882" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_shoulder_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.010773 0.002949 -0.072009" rpy="0 0 0"/>
|
||||||
|
<mass value="0.734"/>
|
||||||
|
<inertia ixx="0.0009988" ixy="-7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="2.86E-05" izz="0.0004354"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_shoulder_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0 -0.00624 -0.1032" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_roll_link"/>
|
||||||
|
<child link="right_shoulder_yaw_link"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_elbow_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.064956 -0.004454 -0.010062" rpy="0 0 0"/>
|
||||||
|
<mass value="0.6"/>
|
||||||
|
<inertia ixx="0.0002891" ixy="-6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="5.6E-06" izz="0.0004197"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_elbow_joint" type="revolute">
|
||||||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||||||
|
<parent link="right_shoulder_yaw_link"/>
|
||||||
|
<child link="right_elbow_link"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="right_wrist_roll_joint" type="revolute">
|
||||||
|
<origin xyz="0.100 -0.00188791 -0.010" rpy="0 0 0"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<parent link="right_elbow_link"/>
|
||||||
|
<child link="right_wrist_roll_link"/>
|
||||||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_wrist_roll_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.01713944778 -0.00053759094 0.00000048864" rpy="0 0 0"/>
|
||||||
|
<mass value="0.08544498"/>
|
||||||
|
<inertia ixx="0.00004821544023" ixy="0.00000424511021" ixz="0.00000000510599" iyy="0.00003722899093" iyz="0.00000000123525" izz="0.00005482106541"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_roll_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_wrist_pitch_joint" type="revolute">
|
||||||
|
<origin xyz="0.038 0 0" rpy="0 0 0"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<parent link="right_wrist_roll_link"/>
|
||||||
|
<child link="right_wrist_pitch_link"/>
|
||||||
|
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_wrist_pitch_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.02299989837 0.00111685314 -0.00111658096" rpy="0 0 0"/>
|
||||||
|
<mass value="0.48404956"/>
|
||||||
|
<inertia ixx="0.00016579646273" ixy="0.00001231206746" ixz="0.00001231699194" iyy="0.00042954057410" iyz="-0.00000081417712" izz="0.00042953697654"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_pitch_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_wrist_yaw_joint" type="revolute">
|
||||||
|
<origin xyz="0.046 0 0" rpy="0 0 0"/>
|
||||||
|
<axis xyz="0 0 1"/>
|
||||||
|
<parent link="right_wrist_pitch_link"/>
|
||||||
|
<child link="right_wrist_yaw_link"/>
|
||||||
|
<limit effort="5" velocity="22" lower="-1.614429558" upper="1.614429558"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_wrist_yaw_link">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.02200381568 -0.00049485096 0.00053861123" rpy="0 0 0"/>
|
||||||
|
<mass value="0.08457647"/>
|
||||||
|
<inertia ixx="0.00004929128828" ixy="0.00000045735494" ixz="0.00000445867591" iyy="0.00005973338134" iyz="-0.00000043217198" izz="0.00003928083826"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_wrist_yaw_link.STL"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint name="right_hand_palm_joint" type="fixed">
|
||||||
|
<origin xyz="0.0415 -0.003 0" rpy="0 0 0"/>
|
||||||
|
<parent link="right_wrist_yaw_link"/>
|
||||||
|
<child link="right_rubber_hand"/>
|
||||||
|
</joint>
|
||||||
|
<link name="right_rubber_hand">
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0.05361310808 0.00295905240 0.00215413091" rpy="0 0 0"/>
|
||||||
|
<mass value="0.170"/>
|
||||||
|
<inertia ixx="0.00010099485234748" ixy="-0.00003618590790516" ixz="-0.00000074301518642" iyy="0.00028135871571621" iyz="-0.00000330189743286" izz="0.00021894770413514"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="meshes/right_rubber_hand.STL"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
</robot>
|
162
resources/robots/g1_description/g1_dual_arm.xml
Normal file
162
resources/robots/g1_description/g1_dual_arm.xml
Normal file
@ -0,0 +1,162 @@
|
|||||||
|
<mujoco model="g1_dual_arm">
|
||||||
|
<compiler angle="radian" meshdir="meshes"/>
|
||||||
|
|
||||||
|
<asset>
|
||||||
|
<mesh name="waist_yaw_link" file="waist_yaw_link.STL"/>
|
||||||
|
<mesh name="waist_roll_link" file="waist_roll_link.STL"/>
|
||||||
|
<mesh name="torso_link" file="torso_link.STL"/>
|
||||||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||||||
|
<mesh name="head_link" file="head_link.STL"/>
|
||||||
|
<mesh name="waist_support_link" file="waist_support_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||||||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="left_wrist_yaw_link" file="left_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="left_rubber_hand" file="left_rubber_hand.STL"/>
|
||||||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||||||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||||||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||||||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||||||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||||||
|
<mesh name="right_wrist_yaw_link" file="right_wrist_yaw_link.STL"/>
|
||||||
|
<mesh name="right_rubber_hand" file="right_rubber_hand.STL"/>
|
||||||
|
</asset>
|
||||||
|
|
||||||
|
<worldbody>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
|
||||||
|
<geom pos="-0.0039635 0 0.035" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
|
||||||
|
<geom pos="-0.0039635 0 0.054" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom pos="-0.0039635 0 0.054" type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="waist_support_link"/>
|
||||||
|
<body name="left_shoulder_pitch_link" pos="-7.2e-06 0.10022 0.29178" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
|
||||||
|
<inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
|
||||||
|
<body name="left_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
|
||||||
|
<body name="left_wrist_roll_link" pos="0.1 0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 0.000537591 4.8864e-07" quat="0.575338 0.411667 -0.574906 0.411094" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_roll_link"/>
|
||||||
|
<body name="left_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 -0.00111685 -0.00111658" quat="0.249998 0.661363 0.293036 0.643608" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_pitch_link"/>
|
||||||
|
<body name="left_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 0.000191745 0.00161742" quat="0.510571 0.526295 0.468078 0.493188" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
<body name="right_shoulder_pitch_link" pos="-7.2e-06 -0.10021 0.29178" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
|
||||||
|
<inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
|
||||||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
|
||||||
|
<geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
|
||||||
|
<inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
|
||||||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
|
||||||
|
<geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
|
||||||
|
<body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
|
||||||
|
<inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
|
||||||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
|
||||||
|
<body name="right_elbow_link" pos="0.015783 0 -0.080518">
|
||||||
|
<inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
|
||||||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
|
||||||
|
<body name="right_wrist_roll_link" pos="0.1 -0.00188791 -0.01">
|
||||||
|
<inertial pos="0.0171394 -0.000537591 4.8864e-07" quat="0.411667 0.575338 -0.411094 0.574906" mass="0.085445" diaginertia="5.48211e-05 4.96646e-05 3.57798e-05"/>
|
||||||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.97222 1.97222" actuatorfrcrange="-25 25"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_roll_link"/>
|
||||||
|
<body name="right_wrist_pitch_link" pos="0.038 0 0">
|
||||||
|
<inertial pos="0.0229999 0.00111685 -0.00111658" quat="0.643608 0.293036 0.661363 0.249998" mass="0.48405" diaginertia="0.000430353 0.000429873 0.000164648"/>
|
||||||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_pitch_link"/>
|
||||||
|
<body name="right_wrist_yaw_link" pos="0.046 0 0">
|
||||||
|
<inertial pos="0.0708244 -0.000191745 0.00161742" quat="0.493188 0.468078 0.526295 0.510571" mass="0.254576" diaginertia="0.000646113 0.000559993 0.000147566"/>
|
||||||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.61443 1.61443" actuatorfrcrange="-5 5"/>
|
||||||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_wrist_yaw_link"/>
|
||||||
|
<geom pos="0.0415 -0.003 0" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_rubber_hand"/>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</body>
|
||||||
|
</worldbody>
|
||||||
|
|
||||||
|
<actuator>
|
||||||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||||||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||||||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||||||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||||||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||||||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||||||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||||||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||||||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||||||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||||||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||||||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||||||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||||||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||||||
|
</actuator>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- setup scene -->
|
||||||
|
<statistic center="1.0 0.7 1.0" extent="0.8"/>
|
||||||
|
<visual>
|
||||||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||||||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||||||
|
<global azimuth="-140" elevation="-20"/>
|
||||||
|
</visual>
|
||||||
|
<asset>
|
||||||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||||||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||||||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||||||
|
</asset>
|
||||||
|
<worldbody>
|
||||||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||||||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||||||
|
</worldbody>
|
||||||
|
</mujoco>
|
BIN
resources/robots/g1_description/images/g1_23dof.png
Normal file
BIN
resources/robots/g1_description/images/g1_23dof.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 912 KiB |
BIN
resources/robots/g1_description/images/g1_29dof.png
Normal file
BIN
resources/robots/g1_description/images/g1_29dof.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 920 KiB |
BIN
resources/robots/g1_description/images/g1_29dof_with_hand.png
Normal file
BIN
resources/robots/g1_description/images/g1_29dof_with_hand.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 922 KiB |
BIN
resources/robots/g1_description/images/g1_dual_arm.png
Normal file
BIN
resources/robots/g1_description/images/g1_dual_arm.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 827 KiB |
BIN
resources/robots/g1_description/meshes/head_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/head_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_ankle_pitch_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_ankle_pitch_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_ankle_roll_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_ankle_roll_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_elbow_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_elbow_link.STL
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_hand_palm_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_hand_palm_link.STL
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_hip_pitch_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_hip_pitch_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_hip_roll_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_hip_roll_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_hip_yaw_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_hip_yaw_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_knee_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_knee_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_rubber_hand.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_rubber_hand.STL
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_wrist_pitch_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_wrist_pitch_link.STL
Normal file
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_wrist_roll_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_wrist_roll_link.STL
Normal file
Binary file not shown.
Binary file not shown.
BIN
resources/robots/g1_description/meshes/left_wrist_yaw_link.STL
Normal file
BIN
resources/robots/g1_description/meshes/left_wrist_yaw_link.STL
Normal file
Binary file not shown.
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user