Skip to content

Commit

Permalink
ergoCubV1* regenerate all the models with the imus in the feet
Browse files Browse the repository at this point in the history
  • Loading branch information
Nicogene committed Feb 12, 2024
1 parent f128b42 commit 3c77a9a
Show file tree
Hide file tree
Showing 10 changed files with 608 additions and 0 deletions.
68 changes: 68 additions & 0 deletions urdf/creo2urdf/data/ergocub1_0/ERGOCUB_all_options_gazebo.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1233,6 +1233,74 @@ reverseRotationAxis:
r_pinkie_dist

XMLBlobs:
# left foot IMU (front)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_front_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# left foot IMU (rear)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# right foot IMU (front)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_front_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# right foot IMU (rear)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# imu waist (workaround since simmechanics was not updated)
- |
<link name="waist_imu_0"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1542,6 +1542,74 @@ reverseRotationAxis:
r_pinkie_dist

XMLBlobs:
# left foot IMU (front)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_front_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# left foot IMU (rear)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# right foot IMU (front)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_front_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# right foot IMU (rear)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# imu waist (workaround since simmechanics was not updated)
- |
<link name="waist_imu_0"/>
Expand Down
68 changes: 68 additions & 0 deletions urdf/creo2urdf/data/ergocub1_1/ERGOCUB_all_options_gazebo.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1246,6 +1246,74 @@ reverseRotationAxis:
r_pinkie_prox

XMLBlobs:
# left foot IMU (front)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_front_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# left foot IMU (rear)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# right foot IMU (front)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_front_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# right foot IMU (rear)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# imu waist (workaround since simmechanics was not updated)
- |
<link name="waist_imu_0"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1546,6 +1546,74 @@ reverseRotationAxis:
r_pinkie_prox

XMLBlobs:
# left foot IMU (front)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_front_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# left foot IMU (rear)
- |
<gazebo reference="l_ankle_2">
<sensor name="l_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# right foot IMU (front)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_front_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
# right foot IMU (rear)
- |
<gazebo reference="r_ankle_2">
<sensor name="r_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
- |
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
# imu waist (workaround since simmechanics was not updated)
- |
<link name="waist_imu_0"/>
Expand Down
56 changes: 56 additions & 0 deletions urdf/ergoCub/robots/ergoCubGazeboV1/model.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -2893,6 +2893,62 @@
<child link="l_hand_pinkie_skin_11"/>
<dynamics damping="0.1"/>
</joint>
<gazebo reference="l_ankle_2">
<sensor name="l_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
<sensor name="l_foot_front_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
<gazebo reference="l_ankle_2">
<sensor name="l_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
<parent link="l_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
<gazebo reference="r_ankle_2">
<sensor name="r_foot_front_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
<sensor name="r_foot_front_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
</sensor>
<gazebo reference="r_ankle_2">
<sensor name="r_foot_rear_ft_imu" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
<parent link="r_ankle_2" />
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
</sensor>
<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"/>
Expand Down
Loading

0 comments on commit 3c77a9a

Please sign in to comment.