Skip to content

Commit 269a20b

Browse files
[ergoCubGazeboV1_*] Use XML blob to add feet IMU in the urdf model generation
1 parent e0054aa commit 269a20b

File tree

2 files changed

+136
-88
lines changed

2 files changed

+136
-88
lines changed

urdf/creo2urdf/data/ergocub1_0/ERGOCUB_all_options.yaml

+68-44
Original file line numberDiff line numberDiff line change
@@ -805,50 +805,6 @@ forceTorqueSensors:
805805
806806
807807
sensors:
808-
- frameName: SCSYS_L_ANKLE_2_FT_FRONT
809-
linkName: l_ankle_2
810-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
811-
sensorName: l_foot_front_ft_imu
812-
sensorType: "accelerometer"
813-
updateRate: "100"
814-
sensorBlobs:
815-
- |
816-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
817-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
818-
</plugin>
819-
- frameName: SCSYS_L_ANKLE_2_FT_REAR
820-
linkName: l_ankle_2
821-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
822-
sensorName: l_foot_rear_ft_imu
823-
sensorType: "accelerometer"
824-
updateRate: "100"
825-
sensorBlobs:
826-
- |
827-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
828-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
829-
</plugin>
830-
- frameName: SCSYS_R_ANKLE_2_FT_FRONT
831-
linkName: r_ankle_2
832-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
833-
sensorName: r_foot_front_ft_imu
834-
sensorType: "accelerometer"
835-
updateRate: "100"
836-
sensorBlobs:
837-
- |
838-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
839-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
840-
</plugin>
841-
- frameName: SCSYS_R_ANKLE_2_FT_REAR
842-
linkName: r_ankle_2
843-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
844-
sensorName: r_foot_rear_ft_imu
845-
sensorType: "accelerometer"
846-
updateRate: "100"
847-
sensorBlobs:
848-
- |
849-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
850-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
851-
</plugin>
852808
- frameName: SCSYS_HEAD_IMU
853809
linkName: head
854810
sensorName: head_imu_0
@@ -1092,6 +1048,74 @@ reverseRotationAxis:
10921048
r_pinkie_dist
10931049

10941050
XMLBlobs:
1051+
# left foot IMU (front)
1052+
- |
1053+
<gazebo reference="l_ankle_2">
1054+
<sensor name="l_foot_front_ft_imu" type="imu">
1055+
<always_on>1</always_on>
1056+
<update_rate>100</update_rate>
1057+
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1058+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1059+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
1060+
</plugin>
1061+
</sensor>
1062+
</gazebo>
1063+
- |
1064+
<sensor name="l_foot_front_ft_imu" type="accelerometer">
1065+
<parent link="l_ankle_2" />
1066+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
1067+
</sensor>
1068+
# left foot IMU (rear)
1069+
- |
1070+
<gazebo reference="l_ankle_2">
1071+
<sensor name="l_foot_rear_ft_imu" type="imu">
1072+
<always_on>1</always_on>
1073+
<update_rate>100</update_rate>
1074+
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1075+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1076+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
1077+
</plugin>
1078+
</sensor>
1079+
</gazebo>
1080+
- |
1081+
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
1082+
<parent link="l_ankle_2" />
1083+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
1084+
</sensor>
1085+
# right foot IMU (front)
1086+
- |
1087+
<gazebo reference="r_ankle_2">
1088+
<sensor name="r_foot_front_ft_imu" type="imu">
1089+
<always_on>1</always_on>
1090+
<update_rate>100</update_rate>
1091+
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1092+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1093+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
1094+
</plugin>
1095+
</sensor>
1096+
</gazebo>
1097+
- |
1098+
<sensor name="r_foot_front_ft_imu" type="accelerometer">
1099+
<parent link="r_ankle_2" />
1100+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
1101+
</sensor>
1102+
# right foot IMU (rear)
1103+
- |
1104+
<gazebo reference="r_ankle_2">
1105+
<sensor name="r_foot_rear_ft_imu" type="imu">
1106+
<always_on>1</always_on>
1107+
<update_rate>100</update_rate>
1108+
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1109+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1110+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
1111+
</plugin>
1112+
</sensor>
1113+
</gazebo>
1114+
- |
1115+
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
1116+
<parent link="r_ankle_2" />
1117+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
1118+
</sensor>
10951119
# imu waist (workaround since simmechanics was not updated)
10961120
- |
10971121
<link name="waist_imu_0"/>

urdf/creo2urdf/data/ergocub1_1/ERGOCUB_all_options.yaml

+68-44
Original file line numberDiff line numberDiff line change
@@ -803,50 +803,6 @@ forceTorqueSensors:
803803
804804
805805
sensors:
806-
- frameName: SCSYS_L_ANKLE_2_FT_FRONT
807-
linkName: l_ankle_2
808-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
809-
sensorName: l_foot_front_ft_imu
810-
sensorType: "accelerometer"
811-
updateRate: "100"
812-
sensorBlobs:
813-
- |
814-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
815-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
816-
</plugin>
817-
- frameName: SCSYS_L_ANKLE_2_FT_REAR
818-
linkName: l_ankle_2
819-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
820-
sensorName: l_foot_rear_ft_imu
821-
sensorType: "accelerometer"
822-
updateRate: "100"
823-
sensorBlobs:
824-
- |
825-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
826-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
827-
</plugin>
828-
- frameName: SCSYS_R_ANKLE_2_FT_FRONT
829-
linkName: r_ankle_2
830-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
831-
sensorName: r_foot_front_ft_imu
832-
sensorType: "accelerometer"
833-
updateRate: "100"
834-
sensorBlobs:
835-
- |
836-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
837-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
838-
</plugin>
839-
- frameName: SCSYS_R_ANKLE_2_FT_REAR
840-
linkName: r_ankle_2
841-
exportFrameInURDF: No # This is not since the frame is already exported in the forceTorqueSensors
842-
sensorName: r_foot_rear_ft_imu
843-
sensorType: "accelerometer"
844-
updateRate: "100"
845-
sensorBlobs:
846-
- |
847-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
848-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
849-
</plugin>
850806
- frameName: SCSYS_HEAD_IMU
851807
linkName: head
852808
sensorName: head_imu_0
@@ -1095,6 +1051,74 @@ reverseRotationAxis:
10951051
r_pinkie_prox
10961052

10971053
XMLBlobs:
1054+
# left foot IMU (front)
1055+
- |
1056+
<gazebo reference="l_ankle_2">
1057+
<sensor name="l_foot_front_ft_imu" type="imu">
1058+
<always_on>1</always_on>
1059+
<update_rate>100</update_rate>
1060+
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1061+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1062+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
1063+
</plugin>
1064+
</sensor>
1065+
</gazebo>
1066+
- |
1067+
<sensor name="l_foot_front_ft_imu" type="accelerometer">
1068+
<parent link="l_ankle_2" />
1069+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
1070+
</sensor>
1071+
# left foot IMU (rear)
1072+
- |
1073+
<gazebo reference="l_ankle_2">
1074+
<sensor name="l_foot_rear_ft_imu" type="imu">
1075+
<always_on>1</always_on>
1076+
<update_rate>100</update_rate>
1077+
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1078+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1079+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
1080+
</plugin>
1081+
</sensor>
1082+
</gazebo>
1083+
- |
1084+
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
1085+
<parent link="l_ankle_2" />
1086+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
1087+
</sensor>
1088+
# right foot IMU (front)
1089+
- |
1090+
<gazebo reference="r_ankle_2">
1091+
<sensor name="r_foot_front_ft_imu" type="imu">
1092+
<always_on>1</always_on>
1093+
<update_rate>100</update_rate>
1094+
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1095+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1096+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
1097+
</plugin>
1098+
</sensor>
1099+
</gazebo>
1100+
- |
1101+
<sensor name="r_foot_front_ft_imu" type="accelerometer">
1102+
<parent link="r_ankle_2" />
1103+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
1104+
</sensor>
1105+
# right foot IMU (rear)
1106+
- |
1107+
<gazebo reference="r_ankle_2">
1108+
<sensor name="r_foot_rear_ft_imu" type="imu">
1109+
<always_on>1</always_on>
1110+
<update_rate>100</update_rate>
1111+
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1112+
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1113+
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
1114+
</plugin>
1115+
</sensor>
1116+
</gazebo>
1117+
- |
1118+
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
1119+
<parent link="r_ankle_2" />
1120+
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
1121+
</sensor>
10981122
# imu waist (workaround since simmechanics was not updated)
10991123
- |
11001124
<link name="waist_imu_0"/>

0 commit comments

Comments
 (0)