Skip to content

Commit 5089634

Browse files
committed
ergoCubGazeboV1_1_minContacts: fix regression after #222
1 parent dbbdd39 commit 5089634

File tree

2 files changed

+8
-132
lines changed

2 files changed

+8
-132
lines changed

urdf/creo2urdf/data/ergocub1_1/ERGOCUB_all_options_minContacts.yaml

-68
Original file line numberDiff line numberDiff line change
@@ -1590,74 +1590,6 @@ reverseRotationAxis:
15901590
r_pinkie_prox
15911591

15921592
XMLBlobs:
1593-
# left foot IMU (front)
1594-
- |
1595-
<gazebo reference="l_ankle_2">
1596-
<sensor name="l_foot_front_ft_imu" type="imu">
1597-
<always_on>1</always_on>
1598-
<update_rate>100</update_rate>
1599-
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1600-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1601-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
1602-
</plugin>
1603-
</sensor>
1604-
</gazebo>
1605-
- |
1606-
<sensor name="l_foot_front_ft_imu" type="accelerometer">
1607-
<parent link="l_ankle_2" />
1608-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
1609-
</sensor>
1610-
# left foot IMU (rear)
1611-
- |
1612-
<gazebo reference="l_ankle_2">
1613-
<sensor name="l_foot_rear_ft_imu" type="imu">
1614-
<always_on>1</always_on>
1615-
<update_rate>100</update_rate>
1616-
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1617-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1618-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
1619-
</plugin>
1620-
</sensor>
1621-
</gazebo>
1622-
- |
1623-
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
1624-
<parent link="l_ankle_2" />
1625-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
1626-
</sensor>
1627-
# right foot IMU (front)
1628-
- |
1629-
<gazebo reference="r_ankle_2">
1630-
<sensor name="r_foot_front_ft_imu" type="imu">
1631-
<always_on>1</always_on>
1632-
<update_rate>100</update_rate>
1633-
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1634-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1635-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
1636-
</plugin>
1637-
</sensor>
1638-
</gazebo>
1639-
- |
1640-
<sensor name="r_foot_front_ft_imu" type="accelerometer">
1641-
<parent link="r_ankle_2" />
1642-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993" />
1643-
</sensor>
1644-
# right foot IMU (rear)
1645-
- |
1646-
<gazebo reference="r_ankle_2">
1647-
<sensor name="r_foot_rear_ft_imu" type="imu">
1648-
<always_on>1</always_on>
1649-
<update_rate>100</update_rate>
1650-
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
1651-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
1652-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
1653-
</plugin>
1654-
</sensor>
1655-
</gazebo>
1656-
- |
1657-
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
1658-
<parent link="r_ankle_2" />
1659-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993" />
1660-
</sensor>
16611593
# imu waist (workaround since simmechanics was not updated)
16621594
- |
16631595
<link name="waist_imu_0"/>

urdf/ergoCub/robots/ergoCubGazeboV1_1_minContacts/model.urdf

+8-64
Original file line numberDiff line numberDiff line change
@@ -1127,8 +1127,8 @@
11271127
</collision>
11281128
</link>
11291129
<joint name="l_index_add" type="revolute">
1130-
<origin xyz="0.022500000000000034 -0.0015000000000006397 -0.06859999999999966" rpy="-8.126657451512497e-16 -0.2967059722446555 1.7414265967526777e-16"/>
1131-
<axis xyz="1.3005559878087045e-15 1.0000000000000002 -1.953448495705706e-15"/>
1130+
<origin xyz="0.022500000000000023 -0.0015000000000006952 -0.0685999999999996" rpy="-8.416895217637947e-16 -0.29670597224465534 5.804755322508926e-17"/>
1131+
<axis xyz="1.1895336853461886e-15 0.9999999999999999 -1.9812040713213337e-15"/>
11321132
<parent link="l_hand_palm"/>
11331133
<child link="l_hand_index_1"/>
11341134
<limit lower="0" upper="0.2617993877991494" effort="1e+9" velocity="1e+9"/>
@@ -1137,7 +1137,7 @@
11371137
<link name="l_hand_index_1">
11381138
<inertial>
11391139
<mass value="0.01923264"/>
1140-
<origin xyz="0.0046807100979840005 0.0038510231744862677 -0.018526526203731464" rpy="0 -0 0"/>
1140+
<origin xyz="0.0046807100979840005 0.0038510231744863237 -0.018526526203731575" rpy="0 -0 0"/>
11411141
<inertia ixx="0.01" ixy="1.4548370851701976e-7" ixz="1.4373172964405972e-7" iyy="0.01" iyz="-6.425403568227921e-7" izz="0.01"/>
11421142
</inertial>
11431143
<visual>
@@ -1427,8 +1427,8 @@
14271427
</collision>
14281428
</link>
14291429
<joint name="l_index_prox" type="revolute">
1430-
<origin xyz="0.009192533346793416 -2.7755575615628914e-17 -0.030713451309624162" rpy="-2.7755575615628914e-16 -7.023611553469422e-10 -7.771561172376094e-16"/>
1431-
<axis xyz="-1.0000000000000002 2.7755575615627613e-17 7.023654366444809e-10"/>
1430+
<origin xyz="0.00919253334679343 0 -0.030713451309624218" rpy="-3.0531133177191815e-16 -7.023611484080483e-10 -7.771561172376096e-16"/>
1431+
<axis xyz="-1 8.326672684688522e-17 7.023654435833748e-10"/>
14321432
<parent link="l_hand_index_1"/>
14331433
<child link="l_hand_index_2"/>
14341434
<limit lower="0" upper="1.5707963267948966" effort="1e+9" velocity="1e+9"/>
@@ -1457,8 +1457,8 @@
14571457
</collision>
14581458
</link>
14591459
<joint name="l_index_dist" type="revolute">
1460-
<origin xyz="-2.7755575615628914e-17 -0.0014999999999999736 -0.039999999999999925" rpy="-7.482326169760975e-8 1.734723475976807e-16 -6.106226635438361e-16"/>
1461-
<axis xyz="-1 -1.804112664227406e-16 9.020562801946248e-17"/>
1460+
<origin xyz="-1.3877787807814457e-17 -0.001500000000000029 -0.03999999999999987" rpy="-7.482326172536535e-8 1.8041124150158794e-16 -6.106226635438361e-16"/>
1461+
<axis xyz="-1 -2.359224176539984e-16 4.163337069211178e-17"/>
14621462
<parent link="l_hand_index_2"/>
14631463
<child link="l_hand_index_3"/>
14641464
<limit lower="0" upper="1.7994344588061537" effort="1e+9" velocity="1e+9"/>
@@ -1467,7 +1467,7 @@
14671467
<link name="l_hand_index_3">
14681468
<inertial>
14691469
<mass value="0.007251413"/>
1470-
<origin xyz="-0.018787329483201373 0.002754671170301093 -0.018853294932697606" rpy="0 -0 0"/>
1470+
<origin xyz="-0.018787329483201345 0.0027546711703011484 -0.018853294932697662" rpy="0 -0 0"/>
14711471
<inertia ixx="0.01" ixy="4.65463304290381e-8" ixz="2.5624287052698965e-7" iyy="0.01" iyz="-2.891156821380605e-7" izz="0.01"/>
14721472
</inertial>
14731473
<visual>
@@ -2764,62 +2764,6 @@
27642764
<parent link="r_hand_thumb_3"/>
27652765
<child link="r_hand_thumb_skin_9"/>
27662766
</joint>
2767-
<gazebo reference="l_ankle_2">
2768-
<sensor name="l_foot_front_ft_imu" type="imu">
2769-
<always_on>1</always_on>
2770-
<update_rate>100</update_rate>
2771-
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
2772-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
2773-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
2774-
</plugin>
2775-
</sensor>
2776-
</gazebo>
2777-
<sensor name="l_foot_front_ft_imu" type="accelerometer">
2778-
<parent link="l_ankle_2"/>
2779-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993"/>
2780-
</sensor>
2781-
<gazebo reference="l_ankle_2">
2782-
<sensor name="l_foot_rear_ft_imu" type="imu">
2783-
<always_on>1</always_on>
2784-
<update_rate>100</update_rate>
2785-
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
2786-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
2787-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_l_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
2788-
</plugin>
2789-
</sensor>
2790-
</gazebo>
2791-
<sensor name="l_foot_rear_ft_imu" type="accelerometer">
2792-
<parent link="l_ankle_2"/>
2793-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993"/>
2794-
</sensor>
2795-
<gazebo reference="r_ankle_2">
2796-
<sensor name="r_foot_front_ft_imu" type="imu">
2797-
<always_on>1</always_on>
2798-
<update_rate>100</update_rate>
2799-
<pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
2800-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
2801-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_front_ft_sensor_inertial.ini</yarpConfigurationFile>
2802-
</plugin>
2803-
</sensor>
2804-
</gazebo>
2805-
<sensor name="r_foot_front_ft_imu" type="accelerometer">
2806-
<parent link="r_ankle_2"/>
2807-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.13525 0 -0.07019999999999993"/>
2808-
</sensor>
2809-
<gazebo reference="r_ankle_2">
2810-
<sensor name="r_foot_rear_ft_imu" type="imu">
2811-
<always_on>1</always_on>
2812-
<update_rate>100</update_rate>
2813-
<pose>0.016000000000000004 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
2814-
<plugin name="ergocub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
2815-
<yarpConfigurationFile>model://ergoCub/conf/gazebo_ergocub_r_foot_rear_ft_sensor_inertial.ini</yarpConfigurationFile>
2816-
</plugin>
2817-
</sensor>
2818-
</gazebo>
2819-
<sensor name="r_foot_rear_ft_imu" type="accelerometer">
2820-
<parent link="r_ankle_2"/>
2821-
<origin rpy="0.0 -0.0 -2.0943952105869315" xyz="0.016000000000000004 0 -0.07019999999999993"/>
2822-
</sensor>
28232767
<link name="waist_imu_0"/>
28242768
<joint name="waist_imu_0_fixed_joint" type="fixed">
28252769
<origin xyz="0.0354497 0.00639688 0.060600" rpy="1.5708 0 -1.5708"/>

0 commit comments

Comments
 (0)