Skip to content

Commit

Permalink
Fix the position of the imu in the waist
Browse files Browse the repository at this point in the history
It fixes #260
  • Loading branch information
Nicogene committed Oct 7, 2024
1 parent 5e40101 commit c4a1fb1
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
6 changes: 3 additions & 3 deletions urdf/creo2urdf/data/ergocub1_0/base_1_0.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1194,7 +1194,7 @@ XMLBlobs:
<link name="waist_imu_0"/>
- |
<joint name="waist_imu_0_fixed_joint" type="fixed">
<origin xyz="0.0354497 0.00639688 0.060600" rpy="1.5708 0 -1.5708"/>
<origin xyz="0.0606 -0.00639428 0.01745" rpy="1.5708 -0.000105208 -1.5708"/>
<parent link="torso_1"/>
<child link="waist_imu_0"/>
<dynamics damping="0.1"/>
Expand All @@ -1216,7 +1216,7 @@ XMLBlobs:
<sensor name="waist_imu_0" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.0354497 0.00639688 0.060600 1.5708 0 -1.5708</pose>
<pose>0.0606 -0.00639428 0.01745 1.5708 -0.000105208 -1.5708</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_waist_inertial.ini</yarpConfigurationFile>
</plugin>
Expand All @@ -1225,7 +1225,7 @@ XMLBlobs:
- |
<sensor name="waist_imu_0" type="accelerometer">
<parent link="torso_1"/>
<origin rpy="1.5708 0 -1.5708" xyz="0.0354497 0.00639688 0.060600"/>
<origin xyz="0.0606 -0.00639428 0.01745" rpy="1.5708 -0.000105208 -1.5708"/>
</sensor>
# upperbody
- |
Expand Down
6 changes: 3 additions & 3 deletions urdf/creo2urdf/data/ergocub1_1/base_1_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1143,7 +1143,7 @@ XMLBlobs:
<link name="waist_imu_0"/>
- |
<joint name="waist_imu_0_fixed_joint" type="fixed">
<origin xyz="0.0354497 0.00639688 0.060600" rpy="1.5708 0 -1.5708"/>
<origin xyz="0.0606 -0.00639428 0.01745" rpy="1.5708 -0.000105208 -1.5708"/>
<parent link="torso_1"/>
<child link="waist_imu_0"/>
<dynamics damping="0.1"/>
Expand All @@ -1159,7 +1159,7 @@ XMLBlobs:
<sensor name="waist_imu_0" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.0354497 0.00639688 0.060600 1.5708 0 -1.5708</pose>
<pose>0.0606 -0.00639428 0.01745 1.5708 -0.000105208 -1.5708</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_waist_inertial.ini</yarpConfigurationFile>
</plugin>
Expand All @@ -1174,7 +1174,7 @@ XMLBlobs:
- |
<sensor name="waist_imu_0" type="accelerometer">
<parent link="torso_1"/>
<origin rpy="1.5708 0 -1.5708" xyz="0.0354497 0.00639688 0.060600"/>
<origin xyz="0.0606 -0.00639428 0.01745" rpy="1.5708 -0.000105208 -1.5708"/>
</sensor>
# upperbody
- |
Expand Down

0 comments on commit c4a1fb1

Please sign in to comment.