Skip to content

Commit eefcc49

Browse files
authored
Absolem: syncronize Xacro with manual edits of model.sdf (#877)
* Absolem: Sync Xacro: Change IMU and friction parameters in Xacro to correspond to the desired values in SDF. * Absolem: Sync Xacro: Re-generate model.sdf using libsdformat 8.9.1 . This commit makes no real change to the geometry of the model, it just represents some numbers and rotations differently.
1 parent d20782e commit eefcc49

File tree

3 files changed

+127
-117
lines changed

3 files changed

+127
-117
lines changed

submitted_models/ctu_cras_norlab_absolem_sensor_config_1/model.sdf

Lines changed: 82 additions & 82 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@
7979
</geometry>
8080
</collision>
8181
<collision name="base_link_fixed_joint_lump__antenna_collision_8">
82-
<pose>-0.39064 0.0789 0.1551 3.1415926535897931 1.5707963267948966 3.1415926535897931</pose>
82+
<pose>-0.39064 0.0789 0.1551 0 1.5707963267948966 0</pose>
8383
<geometry>
8484
<cylinder>
8585
<length>0.03718</length>
@@ -235,7 +235,7 @@
235235
</geometry>
236236
</visual>
237237
<visual name="base_link_fixed_joint_lump__imu_visual_3">
238-
<pose>0 0 0.15 -3.1415926535897931 -0 0</pose>
238+
<pose>0 0 0.15 -3.1415926535897931 0 0</pose>
239239
<geometry>
240240
<box>
241241
<size>0.005 0.005 0.005</size>
@@ -341,15 +341,15 @@
341341
</geometry>
342342
</visual>
343343
<visual name="base_link_fixed_joint_lump__camera_2_visual_16">
344-
<pose>-0.01735 -0.055429 0.314721 -1.5725 0.00415 1.56975</pose>
344+
<pose>-0.01735 -0.055429 0.314721 -1.5725 0.00415 1.56974</pose>
345345
<geometry>
346346
<box>
347347
<size>0.005 0.005 0.005</size>
348348
</box>
349349
</geometry>
350350
</visual>
351351
<visual name="base_link_fixed_joint_lump__camera_2_sim_visual_17">
352-
<pose>-0.01735 -0.055429 0.314721 -0.001705 0.00415 1.56975</pose>
352+
<pose>-0.01735 -0.055429 0.314721 -0.001705 0.00415 1.56974</pose>
353353
<geometry>
354354
<box>
355355
<size>0.005 0.005 0.005</size>
@@ -397,7 +397,7 @@
397397
</geometry>
398398
</visual>
399399
<visual name="base_link_fixed_joint_lump__camera_5_sim_visual_23">
400-
<pose>0.024083 -0.058382 0.376328 3.1415926535897931 -1.5707963267948966 0.945143</pose>
400+
<pose>0.024083 -0.058382 0.376328 -2.19645 -1.5707963267948966 0</pose>
401401
<geometry>
402402
<box>
403403
<size>0.005 0.005 0.005</size>
@@ -474,7 +474,7 @@
474474
</geometry>
475475
</visual>
476476
<visual name="base_link_fixed_joint_lump__camera_link_visual_32">
477-
<pose>0.133719 -0.010853 0.422031 2.07031 -0.013168 1.56329</pose>
477+
<pose>0.133719 -0.010853 0.422031 2.07031 -0.013167 1.56329</pose>
478478
<geometry>
479479
<mesh>
480480
<uri>meshes/realsense_d435.dae</uri>
@@ -639,77 +639,77 @@
639639
<always_on>1</always_on>
640640
<update_rate>50</update_rate>
641641
<imu>
642-
<angular_velocity>
643-
<x>
644-
<noise type="gaussian">
645-
<mean>0</mean>
646-
<stddev>0.009</stddev>
647-
<bias_mean>0.00075</bias_mean>
648-
<bias_stddev>0.005</bias_stddev>
649-
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
650-
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
651-
<precision>0.00025</precision>
652-
</noise>
653-
</x>
654-
<y>
655-
<noise type="gaussian">
656-
<mean>0</mean>
657-
<stddev>0.009</stddev>
658-
<bias_mean>0.00075</bias_mean>
659-
<bias_stddev>0.005</bias_stddev>
660-
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
661-
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
662-
<precision>0.00025</precision>
663-
</noise>
664-
</y>
665-
<z>
666-
<noise type="gaussian">
667-
<mean>0</mean>
668-
<stddev>0.009</stddev>
669-
<bias_mean>0.00075</bias_mean>
670-
<bias_stddev>0.005</bias_stddev>
671-
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
672-
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
673-
<precision>0.00025</precision>
674-
</noise>
675-
</z>
676-
</angular_velocity>
677-
<linear_acceleration>
678-
<x>
679-
<noise type="gaussian">
680-
<mean>0</mean>
681-
<stddev>0.021</stddev>
682-
<bias_mean>0.05</bias_mean>
683-
<bias_stddev>0.0075</bias_stddev>
684-
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
685-
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
686-
<precision>0.005</precision>
687-
</noise>
688-
</x>
689-
<y>
690-
<noise type="gaussian">
691-
<mean>0</mean>
692-
<stddev>0.021</stddev>
693-
<bias_mean>0.05</bias_mean>
694-
<bias_stddev>0.0075</bias_stddev>
695-
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
696-
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
697-
<precision>0.005</precision>
698-
</noise>
699-
</y>
700-
<z>
701-
<noise type="gaussian">
702-
<mean>0</mean>
703-
<stddev>0.021</stddev>
704-
<bias_mean>0.05</bias_mean>
705-
<bias_stddev>0.0075</bias_stddev>
706-
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
707-
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
708-
<precision>0.005</precision>
709-
</noise>
710-
</z>
711-
</linear_acceleration>
712-
</imu>
642+
<angular_velocity>
643+
<x>
644+
<noise type="gaussian">
645+
<mean>0</mean>
646+
<stddev>0.009</stddev>
647+
<bias_mean>0.00075</bias_mean>
648+
<bias_stddev>0.005</bias_stddev>
649+
<dynamic_bias_stddev>2e-05</dynamic_bias_stddev>
650+
<dynamic_bias_correlation_time>400</dynamic_bias_correlation_time>
651+
<precision>0.00025</precision>
652+
</noise>
653+
</x>
654+
<y>
655+
<noise type="gaussian">
656+
<mean>0</mean>
657+
<stddev>0.009</stddev>
658+
<bias_mean>0.00075</bias_mean>
659+
<bias_stddev>0.005</bias_stddev>
660+
<dynamic_bias_stddev>2e-05</dynamic_bias_stddev>
661+
<dynamic_bias_correlation_time>400</dynamic_bias_correlation_time>
662+
<precision>0.00025</precision>
663+
</noise>
664+
</y>
665+
<z>
666+
<noise type="gaussian">
667+
<mean>0</mean>
668+
<stddev>0.009</stddev>
669+
<bias_mean>0.00075</bias_mean>
670+
<bias_stddev>0.005</bias_stddev>
671+
<dynamic_bias_stddev>2e-05</dynamic_bias_stddev>
672+
<dynamic_bias_correlation_time>400</dynamic_bias_correlation_time>
673+
<precision>0.00025</precision>
674+
</noise>
675+
</z>
676+
</angular_velocity>
677+
<linear_acceleration>
678+
<x>
679+
<noise type="gaussian">
680+
<mean>0</mean>
681+
<stddev>0.021</stddev>
682+
<bias_mean>0.05</bias_mean>
683+
<bias_stddev>0.0075</bias_stddev>
684+
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
685+
<dynamic_bias_correlation_time>175</dynamic_bias_correlation_time>
686+
<precision>0.005</precision>
687+
</noise>
688+
</x>
689+
<y>
690+
<noise type="gaussian">
691+
<mean>0</mean>
692+
<stddev>0.021</stddev>
693+
<bias_mean>0.05</bias_mean>
694+
<bias_stddev>0.0075</bias_stddev>
695+
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
696+
<dynamic_bias_correlation_time>175</dynamic_bias_correlation_time>
697+
<precision>0.005</precision>
698+
</noise>
699+
</y>
700+
<z>
701+
<noise type="gaussian">
702+
<mean>0</mean>
703+
<stddev>0.021</stddev>
704+
<bias_mean>0.05</bias_mean>
705+
<bias_stddev>0.0075</bias_stddev>
706+
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
707+
<dynamic_bias_correlation_time>175</dynamic_bias_correlation_time>
708+
<precision>0.005</precision>
709+
</noise>
710+
</z>
711+
</linear_acceleration>
712+
</imu>
713713
<pose>0 0 0.15 -3.1415926535897931 -0 0</pose>
714714
</sensor>
715715
<sensor name="omnicam_sensor0" type="camera">
@@ -996,7 +996,7 @@
996996
</sensor>
997997
</link>
998998
<link name="laser">
999-
<pose>0.2502 0 0.1407 -3.1415926535897931 -0 0</pose>
999+
<pose>0.2502 0 0.1407 -3.1415926535897931 0 0</pose>
10001000
<inertial>
10011001
<pose>0 0 -0.04 0 -0 0</pose>
10021002
<mass>1.1</mass>
@@ -1179,7 +1179,7 @@
11791179
</surface>
11801180
</collision>
11811181
<visual name="front_left_flipper_visual">
1182-
<pose>0 0 0 -2.95744 0 1.5707963267948966</pose>
1182+
<pose>0 0 0 -2.95743 -0 1.5707963267948966</pose>
11831183
<geometry>
11841184
<mesh>
11851185
<uri>meshes/flipper.dae</uri>
@@ -1986,7 +1986,7 @@
19861986
</surface>
19871987
</collision>
19881988
<visual name="rear_left_flipper_visual">
1989-
<pose>0 0 0 -2.95744 0 1.5707963267948966</pose>
1989+
<pose>0 0 0 -2.95743 -0 1.5707963267948966</pose>
19901990
<geometry>
19911991
<mesh>
19921992
<uri>meshes/flipper.dae</uri>
@@ -2408,7 +2408,7 @@
24082408
</surface>
24092409
</collision>
24102410
<visual name="front_right_flipper_visual">
2411-
<pose>0 0 0 -2.95744 -0 -1.5707963267948966</pose>
2411+
<pose>0 0 0 -2.95743 -0 -1.5707963267948966</pose>
24122412
<geometry>
24132413
<mesh>
24142414
<uri>meshes/flipper.dae</uri>
@@ -2759,7 +2759,7 @@
27592759
</surface>
27602760
</collision>
27612761
<visual name="rear_right_flipper_visual">
2762-
<pose>0 0 0 -2.95744 -0 -1.5707963267948966</pose>
2762+
<pose>0 0 0 -2.95743 -0 -1.5707963267948966</pose>
27632763
<geometry>
27642764
<mesh>
27652765
<uri>meshes/flipper.dae</uri>

submitted_models/ctu_cras_norlab_absolem_sensor_config_1/scripts/update_robot_sdf

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,12 @@ MODEL_DIR="${DIR}/.."
77
source "${MODEL_DIR}/config/common.sh"
88
source "${MODEL_DIR}/config/sdf.sh"
99

10+
sdf8_version="$(ign sdf --versions | grep '^8')" || true
11+
[ -z "$sdf8_version" ] && echo "libsdformat8 not found. It is required to update this robot's SDF. Please install libsdformat8-dev and try again." >&2 && exit 1
12+
echo "Found libsdformat ${sdf8_version}" >&2
13+
1014
rosrun xacro xacro "${MODEL_DIR}/urdf/nifti_robot.xacro" ${config} > "${MODEL_DIR}/nifti_robot.sdf.urdf"
11-
ign sdf -p "${MODEL_DIR}/nifti_robot.sdf.urdf" | "${DIR}/high_precision_constants.py" - > "${MODEL_DIR}/model.sdf"
15+
ign sdf --force-version "$sdf8_version" -p "${MODEL_DIR}/nifti_robot.sdf.urdf" | "${DIR}/high_precision_constants.py" - > "${MODEL_DIR}/model.sdf"
1216
sed -i -e 's#model://ctu_cras_norlab_absolem_sensor_config_1/##g' \
1317
-e '/<surface>/{:a;N;/<\/surface>/!ba};/<surface>\n\s*<contact>\n\s*<ode\/>\n\s*<\/contact>\n\s*<friction>\n\s*<ode\/>\n\s*<\/friction>\n\s*<\/surface>/d' \
1418
-e '/<pose>\(-\?0 \?\)\{6\}<\/pose>/d' \

submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/nifti_robot.xacro

Lines changed: 40 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -1185,9 +1185,9 @@
11851185
</contact>
11861186
<friction>
11871187
<ode>
1188-
<mu>1</mu>
1188+
<mu>0.5</mu>
11891189
<mu2>1</mu2>
1190-
<slip1>0.035</slip1>
1190+
<slip1>0.00092</slip1>
11911191
<slip2>0</slip2>
11921192
<fdir1>0 0 1</fdir1>
11931193
</ode>
@@ -1205,9 +1205,9 @@
12051205
</contact>
12061206
<friction>
12071207
<ode>
1208-
<mu>1</mu>
1208+
<mu>0.5</mu>
12091209
<mu2>1</mu2>
1210-
<slip1>0.035</slip1>
1210+
<slip1>0.00092</slip1>
12111211
<slip2>0</slip2>
12121212
<fdir1>0 0 1</fdir1>
12131213
</ode>
@@ -1572,63 +1572,69 @@
15721572
<x>
15731573
<noise type="gaussian">
15741574
<mean>0</mean>
1575-
<stddev>2e-4</stddev>
1576-
<bias_mean>0.0000075</bias_mean>
1577-
<bias_stddev>0.0000008</bias_stddev>
1578-
<dynamic_bias_stddev>0.0000004</dynamic_bias_stddev>
1579-
<dynamic_bias_correlation_time>1000.0</dynamic_bias_correlation_time>
1575+
<stddev>0.009</stddev>
1576+
<bias_mean>0.00075</bias_mean>
1577+
<bias_stddev>0.005</bias_stddev>
1578+
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
1579+
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
1580+
<precision>0.00025</precision>
15801581
</noise>
15811582
</x>
15821583
<y>
15831584
<noise type="gaussian">
15841585
<mean>0</mean>
1585-
<stddev>2e-4</stddev>
1586-
<bias_mean>0.0000075</bias_mean>
1587-
<bias_stddev>0.0000008</bias_stddev>
1588-
<dynamic_bias_stddev>0.0000004</dynamic_bias_stddev>
1589-
<dynamic_bias_correlation_time>1000.0</dynamic_bias_correlation_time>
1586+
<stddev>0.009</stddev>
1587+
<bias_mean>0.00075</bias_mean>
1588+
<bias_stddev>0.005</bias_stddev>
1589+
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
1590+
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
1591+
<precision>0.00025</precision>
15901592
</noise>
15911593
</y>
15921594
<z>
15931595
<noise type="gaussian">
15941596
<mean>0</mean>
1595-
<stddev>2e-4</stddev>
1596-
<bias_mean>0.0000075</bias_mean>
1597-
<bias_stddev>0.0000008</bias_stddev>
1598-
<dynamic_bias_stddev>0.0000004</dynamic_bias_stddev>
1599-
<dynamic_bias_correlation_time>1000.0</dynamic_bias_correlation_time>
1597+
<stddev>0.009</stddev>
1598+
<bias_mean>0.00075</bias_mean>
1599+
<bias_stddev>0.005</bias_stddev>
1600+
<dynamic_bias_stddev>0.00002</dynamic_bias_stddev>
1601+
<dynamic_bias_correlation_time>400.0</dynamic_bias_correlation_time>
1602+
<precision>0.00025</precision>
16001603
</noise>
16011604
</z>
16021605
</angular_velocity>
16031606
<linear_acceleration>
16041607
<x>
16051608
<noise type="gaussian">
16061609
<mean>0</mean>
1607-
<stddev>1e-2</stddev>
1608-
<bias_mean>0.1</bias_mean>
1609-
<bias_stddev>0.001</bias_stddev>
1610-
<dynamic_bias_stddev>0.002</dynamic_bias_stddev>
1611-
<dynamic_bias_correlation_time>300.0</dynamic_bias_correlation_time>
1610+
<stddev>0.021</stddev>
1611+
<bias_mean>0.05</bias_mean>
1612+
<bias_stddev>0.0075</bias_stddev>
1613+
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
1614+
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
1615+
<precision>0.005</precision>
16121616
</noise>
16131617
</x>
16141618
<y>
16151619
<noise type="gaussian">
16161620
<mean>0</mean>
1617-
<stddev>1e-2</stddev>
1618-
<bias_mean>0.1</bias_mean>
1619-
<bias_stddev>0.001</bias_stddev>
1620-
<dynamic_bias_stddev>0.002</dynamic_bias_stddev>
1621-
<dynamic_bias_correlation_time>300.0</dynamic_bias_correlation_time>
1621+
<stddev>0.021</stddev>
1622+
<bias_mean>0.05</bias_mean>
1623+
<bias_stddev>0.0075</bias_stddev>
1624+
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
1625+
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
1626+
<precision>0.005</precision>
16221627
</noise>
16231628
</y>
16241629
<z>
16251630
<noise type="gaussian">
16261631
<mean>0</mean>
1627-
<stddev>1e-2</stddev>
1628-
<bias_mean>0.1</bias_mean>
1629-
<bias_stddev>0.001</bias_stddev>
1630-
<dynamic_bias_stddev>0.002</dynamic_bias_stddev>
1631-
<dynamic_bias_correlation_time>300.0</dynamic_bias_correlation_time>
1632+
<stddev>0.021</stddev>
1633+
<bias_mean>0.05</bias_mean>
1634+
<bias_stddev>0.0075</bias_stddev>
1635+
<dynamic_bias_stddev>0.000375</dynamic_bias_stddev>
1636+
<dynamic_bias_correlation_time>175.0</dynamic_bias_correlation_time>
1637+
<precision>0.005</precision>
16321638
</noise>
16331639
</z>
16341640
</linear_acceleration>

0 commit comments

Comments
 (0)