add imu_in_pelvis for g1
This commit is contained in:
parent
e6b9e8c669
commit
ae724a1383
|
@ -579,11 +579,18 @@
|
|||
</joint>
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<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_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 -->
|
||||
|
|
|
@ -40,6 +40,7 @@
|
|||
<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"/>
|
||||
|
@ -130,7 +131,7 @@
|
|||
<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" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||
<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"/>
|
||||
|
@ -222,8 +223,10 @@
|
|||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
<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>
|
||||
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<robot name="g1_23dof">
|
||||
<robot name="g1_23dof_rev_1_0">
|
||||
<mujoco>
|
||||
<compiler meshdir="meshes" discardvisual="false"/>
|
||||
</mujoco>
|
||||
|
@ -530,11 +530,18 @@
|
|||
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<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_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 -->
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<mujoco model="g1_23dof">
|
||||
<mujoco model="g1_23dof_rev_1_0">
|
||||
<compiler angle="radian" meshdir="meshes"/>
|
||||
|
||||
<asset>
|
||||
|
@ -38,6 +38,7 @@
|
|||
<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"/>
|
||||
|
@ -125,7 +126,7 @@
|
|||
<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" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||||
<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"/>
|
||||
|
@ -217,8 +218,10 @@
|
|||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
<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>
|
||||
|
||||
|
||||
|
|
|
@ -604,11 +604,18 @@
|
|||
</joint>
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<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_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 -->
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
<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"/>
|
||||
|
@ -144,7 +145,7 @@
|
|||
<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" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||
<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"/>
|
||||
|
@ -270,8 +271,10 @@
|
|||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
<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>
|
||||
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<robot name="g1_29dof">
|
||||
<robot name="g1_29dof_rev_1_0">
|
||||
<mujoco>
|
||||
<compiler meshdir="meshes" discardvisual="false"/>
|
||||
</mujoco>
|
||||
|
@ -576,11 +576,18 @@
|
|||
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<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_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 -->
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<mujoco model="g1_29dof">
|
||||
<mujoco model="g1_29dof_rev_1_0">
|
||||
<compiler angle="radian" meshdir="meshes"/>
|
||||
|
||||
<asset>
|
||||
|
@ -46,6 +46,7 @@
|
|||
<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"/>
|
||||
|
@ -141,7 +142,7 @@
|
|||
<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" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||||
<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"/>
|
||||
|
@ -267,8 +268,10 @@
|
|||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
<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>
|
||||
|
||||
|
||||
|
|
|
@ -604,11 +604,18 @@
|
|||
</joint>
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<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_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 -->
|
||||
|
|
|
@ -61,6 +61,7 @@
|
|||
<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"/>
|
||||
|
@ -158,7 +159,7 @@
|
|||
<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" size="0.01" pos="-0.03959 -0.00224 0.13792"/>
|
||||
<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"/>
|
||||
|
@ -384,8 +385,10 @@
|
|||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
<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>
|
||||
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<robot name="g1_29dof_with_hand">
|
||||
<robot name="g1_29dof_with_hand_rev_1_0">
|
||||
<mujoco>
|
||||
<compiler meshdir="meshes" discardvisual="false"/>
|
||||
</mujoco>
|
||||
|
@ -576,11 +576,18 @@
|
|||
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<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_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 -->
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<mujoco model="g1_29dof_with_hand">
|
||||
<mujoco model="g1_29dof_with_hand_rev_1_0">
|
||||
<compiler angle="radian" meshdir="meshes"/>
|
||||
|
||||
<asset>
|
||||
|
@ -60,6 +60,7 @@
|
|||
<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"/>
|
||||
|
@ -155,7 +156,7 @@
|
|||
<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" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
|
||||
<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"/>
|
||||
|
@ -381,8 +382,10 @@
|
|||
</actuator>
|
||||
|
||||
<sensor>
|
||||
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||||
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||||
<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>
|
||||
|
||||
|
||||
|
|
|
@ -168,11 +168,18 @@
|
|||
</joint>
|
||||
|
||||
<!-- IMU -->
|
||||
<link name="imu_link"></link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<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_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 -->
|
||||
|
|
Loading…
Reference in New Issue