-
Notifications
You must be signed in to change notification settings - Fork 99
/
Copy pathurban_circuit.ign
1431 lines (1325 loc) · 59.1 KB
/
urban_circuit.ign
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
<?xml version="1.0"?>
<!-- Usage: ign launch urban_circuit.ign
[worldName:=<worldName>
robotName1:=<robotName> robotConfig1:=<robotConfig>
robotName2:=<robotName> robotConfig2:=<robotConfig>
marsupial1:=<robotName>:<robotName>
... ]
The [worldName] command line argument is optional,
defaults to urban_qual if not specified
The [robotNameX] command line argument is optional, where X can be 1 to 20
Example that loads urban circuit world with an X2 robot with configuration 3
ign launch urban_circuit.ign worldName:=urban_qual
robotName1:=X2_3 robotConfig1:=X2_SENSOR_CONFIG_3
-->
<%
# Needed for adding marsupial robots
require "rexml/document"
%>
<%
# When 'enableGroundTruth = true' absolute poses of vehicles will be published.
# This is useful for debugging purposes, but will not be available during
# competition scoring.
# Check if enableGroundTruith is not defined or is empty/nil
if !defined?(enableGroundTruth) || enableGroundTruth == nil || enableGroundTruth.empty?
$enableGroundTruth = false
else
$enableGroundTruth = enableGroundTruth
end
# Check if circuit is not defined or is empty/nil
if !defined?(circuit) || circuit == nil || circuit.empty?
$circuit = 'urban'
else
$circuit = circuit
end
%>
<%
Vector3d = Struct.new(:x, :y, :z)
AngularVector3d = Struct.new(:roll, :pitch, :yaw)
class Robot
attr_accessor :name, :config, :type, :configNumber, :pos, :rot
def initialize(name, config)
@name = name
@config = config
match = config.match(/(.*)_SENSOR_CONFIG/)
if match.nil?
@type = config
else
@type = match[1] unless match.nil?
end
@configNumber = config[-1]
@pos = Vector3d.new(0, 0, 0)
@rot = AngularVector3d.new(0, 0, 0)
end
end
$commsFadingExponent = 2.5
if $circuit == "cave"
$commsFadingExponent = 1.5
end
# spawn world offset
if $circuit == "urban"
spawnWorldXPos = 6
spawnWorldYPos = 27
spawnWorldZPos = 7.5
spawnWorldYaw = 0
guiCameraPose = "-2.0 27 15 0 0.868 0"
else
spawnWorldXPos = 0
spawnWorldYPos = 0
spawnWorldZPos = 0
spawnWorldYaw = 0
guiCameraPose = "-6.3 -4.2 3.6 0 0.268 0.304"
end
teamBaseSpawned = false
# Check if robotNameX and robotConfigX exists
spawnRowSize = 4
spawnColSize = 5
spawnGridSize = 2
maxRobotCount = spawnRowSize * spawnColSize
spawnColOffset = spawnColSize * spawnGridSize / 2
spawnRowOffset = spawnRowSize * spawnGridSize / 2
robots = Hash.new
for i in 1..maxRobotCount do
if (local_variables.include?(:"robotName#{i}") &&
local_variables.include?(:"robotConfig#{i}"))
name=eval "robotName#{i}"
config=eval "robotConfig#{i}"
if name != nil && !name.empty?
raise "Duplicate robot name #{name}" if robots.has_key? name
robots[name] = Robot.new(name, config)
end
end
end
MARSUPIAL_PARENT_LINK_NAMES = {
"X1" => "base_link",
"EXPLORER_X1" => "base_link",
"EXPLORER_R2" => "Rear_Rocker_Link",
"CSIRO_DATA61_OZBOT_ATR" => "base_link"
}
MARSUPIAL_VALID_ROBOT_PAIRS = {
"X1" => ["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN"],
"EXPLORER_X1" =>["X3", "MARBLE_QAV500", "CERBERUS_GAGARIN"],
"EXPLORER_R2" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4", "EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN"],
"CSIRO_DATA61_OZBOT_ATR" =>["X3", "X4", "SSCI_X4", "SOPHISTICATED_ENGINEERING_X4","EXPLORER_DS1", "MARBLE_QAV500", "CERBERUS_M100", "CERBERUS_GAGARIN"]
}
MARSUPIAL_PARENT_ROBOT_POSITION_OFFSETS = {
"X1" => Vector3d.new(0, 0, 0.717),
"EXPLORER_X1" => Vector3d.new(0, 0, 0.717),
"EXPLORER_R2" => Vector3d.new(-0.402375, 0, 0.6874),
"CSIRO_DATA61_OZBOT_ATR" => Vector3d.new(-0.15, 0, 0.528)
}
MARSUPIAL_PARENT_ROBOT_ROTATION_OFFSETS = {
"X1" => AngularVector3d.new(0, 0, 0),
"EXPLORER_X1" => AngularVector3d.new(0, 0, 0),
"EXPLORER_R2" => AngularVector3d.new(0, 0, -3.1416),
"CSIRO_DATA61_OZBOT_ATR" => AngularVector3d.new(0, 0, -3.1416)
}
allExecutables = ""
# key: parent, value: child
marsupialParents = Hash.new
# The logic for validating marsupial robots is:
# * Check that parent names are unique
# * Check that child names are unique
# * Check that each parent and child robot is in the list of robots to be spawned
# * Check that parent robots are in the MARSUPIAL_VALID_ROBOT_PAIRS list
# * Check that child robots are in the MARSUPIAL_VALID_ROBOT_PAIRS list
# These criteria ensure that the robots specified in the "marsupial" variables are valid
# and that there is a one-to-one relationship between parent and child robots
# Handle marsupial robots
for i in 1..maxRobotCount do
if local_variables.include?(:"marsupial#{i}")
parent, child = (eval "marsupial#{i}").split(':')
# Check that parent names are unique
if marsupialParents.has_key?(parent)
raise "Invalid marsupial configuration: The parent robot [#{parent}] cannot be used more than once"
end
# Check that child names are unique
if marsupialParents.has_value?(child)
raise "Invalid marsupial configuration: The child robot [#{child}] cannot be used more than once"
end
# Check that each parent and child robot is in the list of robots to be spawned
unless robots.has_key?(parent)
raise "Invalid marsupial configuration: The parent robot [#{parent}] is not in the list of robots to be spawned"
end
unless robots.has_key?(child)
raise "Invalid marsupial configuration: The child robot [#{child}] is not in the list of robots to be spawned"
end
parentType = robots[parent].type
childType = robots[child].type
# Check that parent robots are in the MARSUPIAL_VALID_ROBOT_PAIRS hash
unless MARSUPIAL_VALID_ROBOT_PAIRS.key?(parentType)
raise "Invalid marsupial configuration: The parent robot [#{parent}] with type [#{parentType}] is not in the list of robots allowed to be marsupial parents. The list is #{MARSUPIAL_VALID_ROBOT_PAIRS}"
end
# Check that child robots are in the MARSUPIAL_VALID_ROBOT_PARIS hash
unless MARSUPIAL_VALID_ROBOT_PAIRS[parentType].include?(childType)
raise "Invalid marsupial configuration: The child robot [#{child}] with type [#{childType}] is not in the list of robots allowed to be marsupial children: The list is #{MARSUPIAL_VALID_ROBOT_PAIRS}"
end
marsupialParents[parent] = child
end
end
%>
<%
# Check if worldName is not defined or is empty/nil
if !defined?(worldName) || worldName == nil || worldName.empty?
$worldName = 'urban_qual'
else
$worldName = worldName
end
if !defined?(headless) || headless == nil || headless.empty?
$headless = false
elsif headless == 'true' || headless == 'True' || headless == '1'
$headless = true
end
# Check if durationSec is not defined or is empty/nil. In this case, set
# durationSec to zero, which equats to an infinite run time.
if !defined?(durationSec) || durationSec == nil || durationSec.empty?
$durationSec = 0
else
$durationSec = durationSec
end
worldNumber = $worldName.split('_').last
# If localModel is set, the model URI will use a local path to the model with
# the assumption that the model is installed in the same workspace as the
# launch file. This only applies to models submitted by teams.
if !defined?(localModel) || localModel == nil || localModel.empty?
$localModel = false
else
$localModel = localModel
end
%>
<%
# disable levels for simple cave worlds
$levels = "true"
if $worldName.include?('simple_cave_')
$levels = "false"
end
if defined?(levels) && levels != nil && !levels.empty?
$levels = levels.downcase == "true"
end
%>
<ignition version='1.0'>
<env>
<name>IGN_GAZEBO_SYSTEM_PLUGIN_PATH</name>
<value>$LD_LIBRARY_PATH</value>
</env>
<!-- Start ROS first. This is a bit hacky for now. -->
<!-- Make sure to source /opt/ros/melodic/setup.bash -->
<executable name='ros'>
<command>roslaunch subt_ros competition_init.launch world_name:=<%=$worldName%> vehicle_topics:=<%=(robots.empty?)?"1":"0"%> enable_ground_truth:=<%=($enableGroundTruth)?"1":"0"%> robot_names:=<%= robots.keys.join(",") %></command>
</executable>
<plugin name="ignition::launch::GazeboServer"
filename="libignition-launch-gazebo.so">
<% if $worldName.include?('tunnel_circuit_') &&
!$worldName.include?('practice') %>
<world_file>tunnel_circuit/<%= worldNumber %>/<%= $worldName %>.sdf</world_file>
<% elsif $worldName.include?('urban_circuit_') &&
!$worldName.include?('practice') %>
<world_file>urban_circuit/<%= worldNumber %>/<%= $worldName %>.sdf</world_file>
<% elsif $worldName.include?('cave_circuit_') &&
!$worldName.include?('practice') %>
<world_file>cave_circuit/<%= worldNumber %>/<%= $worldName %>.sdf</world_file>
<% else %>
<world_file><%= $worldName %>.sdf</world_file>
<% end %>
<%if defined?(updateRate) && updateRate != nil && !updateRate.empty?%>
<update_rate><%= updateRate %></update_rate>
<%end%>
<run>true</run>
<levels><%= $levels %></levels>
<record>
<enabled>true</enabled>
<!-- This path is used by cloudsim, please do not change -->
<path>/tmp/ign/logs</path>
<overwrite>true</overwrite>
</record>
<%if defined?(seed) && seed != nil && !seed.empty?%>
<seed><%= seed %></seed>
<%end%>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-magnetometer-system.so"
name="ignition::gazebo::systems::Magnetometer">
</plugin>
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libignition-gazebo-air-pressure-system.so"
name="ignition::gazebo::systems::AirPressure">
</plugin>
<!-- The SubT challenge logic plugin -->
<plugin entity_name="<%= $worldName %>"
entity_type="world"
filename="libGameLogicPlugin.so"
name="subt::GameLogicPlugin">
<!-- The collection of artifacts to locate -->
<world_name><%= $worldName %></world_name>
<ros>false</ros>
<duration_seconds><%= $durationSec %></duration_seconds>
<logging>
<!-- Use the <path> element to control where to record the log file.
The HOME path is used by default -->
<path>/tmp/ign/logs</path>
<filename_prefix>subt_<%= $circuit %></filename_prefix>
<elevation_step_size>5</elevation_step_size>
</logging>
</plugin>
</plugin>
<%if !$headless %>
<executable_wrapper>
<plugin name="ignition::launch::GazeboGui"
filename="libignition-launch-gazebogui.so">
<world_name><%= $worldName %></world_name>
<window_title>SubT Simulator</window_title>
<window_icon><%= ENV['SUBT_IMAGES_PATH'] %>/SubT_logo.svg</window_icon>
<plugin filename="GzScene3D" name="3D View">
<ignition-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.2 0.2 0.2</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose><%= guiCameraPose %></camera_pose>
</plugin>
<plugin filename="WorldControl" name="World control">
<ignition-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>
<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
<service>/world/<%= $worldName %>/control</service>
<stats_topic>/world/<%= $worldName %>/stats</stats_topic>
</plugin>
<plugin filename="WorldStats" name="World stats">
<ignition-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>
<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
<topic>/world/<%= $worldName %>/stats</topic>
</plugin>
<!-- Entity tree -->
<!-- <plugin filename="EntityTree" name="Entity tree">
<ignition-gui>
<title>Entity tree</title>
</ignition-gui>
</plugin> -->
<!-- Transform Control -->
<!-- <plugin filename="TransformControl" name="Transform Control">
<service>/world/<%= $worldName %>/gui/transform_mode</service>
</plugin> -->
</plugin>
</executable_wrapper>
<%end%>
<!-- The SubT challenge comms broker plugin -->
<plugin entity_name="<%= $worldName %>"
entity_type="world"
name="subt::CommsBrokerPlugin"
filename="libCommsBrokerPlugin.so">
<generate_table>true</generate_table>
<world_name><%= $worldName %></world_name>
<comms_model>
<comms_model_type>visibility_range</comms_model_type>
<range_config>
<max_range>500.0</max_range>
<fading_exponent><%= $commsFadingExponent %></fading_exponent>
<L0>40</L0>
<sigma>10.0</sigma>
</range_config>
<visibility_config>
<visibility_cost_to_fading_exponent>0.2</visibility_cost_to_fading_exponent>
<comms_cost_max>10</comms_cost_max>
</visibility_config>
<radio_config>
<capacity>1000000</capacity>
<tx_power>20</tx_power>
<noise_floor>-90</noise_floor>
<modulation>QPSK</modulation>
</radio_config>
</comms_model>
</plugin>
<!-- The SubT challenge base station plugin -->
<plugin entity_name="base_station"
entity_type="model"
name="subt::BaseStationPlugin"
filename="libBaseStationPlugin.so">
</plugin>
<%
def spawnX1(_name, _config, _x, _y, _z, _yaw)
uav=0
laserScan=0
stereoCam=0
lidar3d=0
if _config == "1" or _config == "2"
laserScan=1
end
if _config == "3" or _config == "4" or _config == "7" or _config == "8"
lidar3d=1
end
if _config == "5"
stereoCam=1
end
max_breadcrumbs = 0
if _config == "7" or _config == "8"
max_breadcrumbs = 12
end
z = _z + 0.2
spawn = <<-HEREDOC
<spawn name='#{_name}'>
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{z} 0 0 #{_yaw}</pose>
<world>#{$worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
<include>
<name>#{_name}</name>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X1 Config #{_config}</uri>
<!-- Diff drive -->
<plugin filename="libignition-gazebo-diff-drive-system.so"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<right_joint>rear_right_wheel_joint</right_joint>
<wheel_separation>#{0.45649 * 1.5}</wheel_separation>
<wheel_radius>0.1651</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-1</min_velocity>
<max_velocity>1</max_velocity>
<min_acceleration>-3</min_acceleration>
<max_acceleration>3</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>
<publish_sensor_pose>true</publish_sensor_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_nested_model_pose>#{$enableGroundTruth}</publish_nested_model_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
<static_publisher>true</static_publisher>
<static_update_frequency>1</static_update_frequency>
</plugin>
<!-- Battery plugin -->
<plugin filename="libignition-gazebo-linearbatteryplugin-system.so"
name="ignition::gazebo::systems::LinearBatteryPlugin">
<battery_name>linear_battery</battery_name>
<voltage>12.694</voltage>
<open_circuit_voltage_constant_coef>12.694</open_circuit_voltage_constant_coef>
<open_circuit_voltage_linear_coef>-3.1424</open_circuit_voltage_linear_coef>
<initial_charge>78.4</initial_charge>
<capacity>78.4</capacity>
<resistance>0.061523</resistance>
<smooth_current_tau>1.9499</smooth_current_tau>
<power_load>6.6</power_load>
<start_on_motion>true</start_on_motion>
</plugin>
<!-- Gas Sensor plugin -->
<plugin filename="libGasEmitterDetectorPlugin.so"
name="subt::GasDetector">
<topic>/model/#{_name}/gas_detected</topic>
<update_rate>10</update_rate>
<type>gas</type>
</plugin>
<plugin filename="libignition-gazebo-breadcrumbs-system.so"
name="ignition::gazebo::systems::Breadcrumbs">
<topic>/model/#{_name}/breadcrumb/deploy</topic>
<max_deployments>#{max_breadcrumbs}</max_deployments>
<disable_physics_time>3.0</disable_physics_time>
<breadcrumb>
<sdf version="1.6">
<model name="#{_name}__breadcrumb__">
<pose>-0.45 0 0 0 0 0</pose>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Breadcrumb Node</uri>
</include>
</model>
</sdf>
</breadcrumb>
</plugin>
<!-- Wheel plugin -->
<plugin filename="libignition-gazebo-wheel-slip-system.so"
name="ignition::gazebo::systems::WheelSlip">
<wheel link_name="front_left_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>138.767</wheel_normal_force>
<wheel_radius>0.1651</wheel_radius>
</wheel>
<wheel link_name="rear_left_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>138.767</wheel_normal_force>
<wheel_radius>0.1651</wheel_radius>
</wheel>
<wheel link_name="front_right_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>138.767</wheel_normal_force>
<wheel_radius>0.1651</wheel_radius>
</wheel>
<wheel link_name="rear_right_wheel">
<slip_compliance_lateral>0.172</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>138.767</wheel_normal_force>
<wheel_radius>0.1651</wheel_radius>
</wheel>
</plugin>
</include>
</sdf>
</spawn>
HEREDOC
exec = <<-HEREDOC
<executable name='x1_description'>
<command>roslaunch --wait subt_ros x1_description.launch world_name:=#{$worldName} name:=#{_name}</command>
</executable>
<executable name='x1_ros_ign_bridge'>
<command>roslaunch --wait subt_ros vehicle_topics.launch world_name:=#{$worldName} name:=#{_name} uav:=#{uav} laser_scan:=#{laserScan} stereo_cam:=#{stereoCam} lidar_3d:=#{lidar3d} breadcrumbs:=#{max_breadcrumbs>0?1:0}</command>
</executable>
HEREDOC
return spawn, exec
end
def spawnX2(_name, _config, _x, _y, _z, _yaw)
uav=0
laserScan=0
stereoCam=0
lidar3d=0
if _config == "1" or _config == "2" or _config == "3" or _config == "4" or _config == "9"
laserScan=1
end
if _config == "5"
stereoCam=1
end
if _config == "6" or _config == "8"
lidar3d=1
end
max_breadcrumbs = 0
if _config == "8" or _config == "9"
max_breadcrumbs = 6
end
z = _z + 0.063494
spawn = <<-HEREDOC
<spawn name='#{_name}'>
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{z} 0 0 #{_yaw}</pose>
<world>#{$worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
<include>
<name>#{_name}</name>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X2 Config #{_config}</uri>
<!-- Diff drive -->
<plugin filename="libignition-gazebo-diff-drive-system.so"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<right_joint>rear_right_wheel_joint</right_joint>
<wheel_separation>#{0.33559 * 1.23}</wheel_separation>
<wheel_radius>0.098</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-2</min_velocity>
<max_velocity>2</max_velocity>
<min_acceleration>-6</min_acceleration>
<max_acceleration>6</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>
<publish_sensor_pose>true</publish_sensor_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_nested_model_pose>#{$enableGroundTruth}</publish_nested_model_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
<static_publisher>true</static_publisher>
<static_update_frequency>1</static_update_frequency>
</plugin>
<!-- Battery plugin -->
<plugin filename="libignition-gazebo-linearbatteryplugin-system.so"
name="ignition::gazebo::systems::LinearBatteryPlugin">
<battery_name>linear_battery</battery_name>
<voltage>12.694</voltage>
<open_circuit_voltage_constant_coef>12.694</open_circuit_voltage_constant_coef>
<open_circuit_voltage_linear_coef>-3.1424</open_circuit_voltage_linear_coef>
<initial_charge>78.4</initial_charge>
<capacity>78.4</capacity>
<resistance>0.061523</resistance>
<smooth_current_tau>1.9499</smooth_current_tau>
<power_load>6.6</power_load>
<start_on_motion>true</start_on_motion>
</plugin>
<!-- Gas Sensor plugin -->
<plugin filename="libGasEmitterDetectorPlugin.so"
name="subt::GasDetector">
<topic>/model/#{_name}/gas_detected</topic>
<update_rate>10</update_rate>
<type>gas</type>
</plugin>
<plugin filename="libignition-gazebo-breadcrumbs-system.so"
name="ignition::gazebo::systems::Breadcrumbs">
<topic>/model/#{_name}/breadcrumb/deploy</topic>
<max_deployments>#{max_breadcrumbs}</max_deployments>
<disable_physics_time>3.0</disable_physics_time>
<breadcrumb>
<sdf version="1.6">
<model name="#{_name}__breadcrumb__">
<pose>-0.24 0 0 0 0 0</pose>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Breadcrumb Node</uri>
</include>
</model>
</sdf>
</breadcrumb>
</plugin>
<!-- Wheel plugin -->
<plugin filename="libignition-gazebo-wheel-slip-system.so"
name="ignition::gazebo::systems::WheelSlip">
<wheel link_name="front_left_wheel">
<slip_compliance_lateral>0.116</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>45.20448</wheel_normal_force>
<wheel_radius>0.098</wheel_radius>
</wheel>
<wheel link_name="rear_left_wheel">
<slip_compliance_lateral>0.116</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>45.20448</wheel_normal_force>
<wheel_radius>0.098</wheel_radius>
</wheel>
<wheel link_name="front_right_wheel">
<slip_compliance_lateral>0.116</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>45.20448</wheel_normal_force>
<wheel_radius>0.098</wheel_radius>
</wheel>
<wheel link_name="rear_right_wheel">
<slip_compliance_lateral>0.116</slip_compliance_lateral>
<slip_compliance_longitudinal>0</slip_compliance_longitudinal>
<wheel_normal_force>45.20448</wheel_normal_force>
<wheel_radius>0.098</wheel_radius>
</wheel>
</plugin>
</include>
</sdf>
</spawn>
HEREDOC
exec = <<-HEREDOC
<executable name='x2_description'>
<command>roslaunch --wait subt_ros x2_description.launch world_name:=#{$worldName} name:=#{_name}</command>
</executable>
<executable name='x2_ros_ign_bridge'>
<command>roslaunch --wait subt_ros vehicle_topics.launch world_name:=#{$worldName} name:=#{_name} uav:=#{uav} laser_scan:=#{laserScan} stereo_cam:=#{stereoCam} lidar_3d:=#{lidar3d} breadcrumbs:=#{max_breadcrumbs>0?1:0}</command>
</executable>
HEREDOC
return spawn, exec
end
def spawnX3(_name, _config, _x, _y, _z, _yaw)
uav=1
laserScan=0
stereoCam=0
rgbdCam=0
if _config == "3" || _config == "4"
rgbdCam=1
end
if _config == "5"
stereoCam=1
end
z = _z + 0.053302
spawn = <<-HEREDOC
<spawn name='#{_name}'>
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{z} 0 0 #{_yaw}</pose>
<world>#{$worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
<include>
<name>#{_name}</name>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X3 UAV Config #{_config}</uri>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>
<publish_sensor_pose>true</publish_sensor_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_nested_model_pose>#{$enableGroundTruth}</publish_nested_model_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
<static_publisher>true</static_publisher>
<static_update_frequency>1</static_update_frequency>
</plugin>
<plugin filename="libignition-gazebo-multicopter-motor-model-system.so"
name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>model/#{_name}</robotNamespace>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>800.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/0</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="libignition-gazebo-multicopter-motor-model-system.so"
name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>model/#{_name}</robotNamespace>
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>800.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="libignition-gazebo-multicopter-motor-model-system.so"
name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>model/#{_name}</robotNamespace>
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>800.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="libignition-gazebo-multicopter-motor-model-system.so"
name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>model/#{_name}</robotNamespace>
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>800.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!--Multicopter velocity controller-->
<plugin
filename="libignition-gazebo-multicopter-control-system.so"
name="ignition::gazebo::systems::MulticopterVelocityControl">
<robotNamespace>model/#{_name}</robotNamespace>
<commandSubTopic>cmd_vel</commandSubTopic>
<motorControlPubTopic>command/motor_speed</motorControlPubTopic>
<enableSubTopic>velocity_controller/enable</enableSubTopic>
<comLinkName>base_link</comLinkName>
<velocityGain>2.7 2.7 2.7</velocityGain>
<attitudeGain>2 3 0.15</attitudeGain>
<angularRateGain>0.4 0.52 0.18</angularRateGain>
<maximumLinearAcceleration>1 1 2</maximumLinearAcceleration>
<maximumLinearVelocity>5 5 5</maximumLinearVelocity>
<maximumAngularVelocity>3 3 3</maximumAngularVelocity>
<linearVelocityNoiseMean>0 0 0.05</linearVelocityNoiseMean>
<!-- linearVelocityNoiseStdDev based on error values reported in the paper Shen et. al., -->
<!-- Vision-Based State Estimation and Trajectory Control Towards High-Speed Flight with a Quadrotor -->
<!-- http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.490.7958&rep=rep1&type=pdf -->
<linearVelocityNoiseStdDev>0.1105 0.1261 0.00947</linearVelocityNoiseStdDev>
<angularVelocityNoiseMean>0 0 0</angularVelocityNoiseMean>
<!-- angularVelocityNoiseStdDev values based on ADIS16448's Rate Noise Density with a sample -->
<!-- time of 0.004 ms. -->
<angularVelocityNoiseStdDev>0.004 0.004 0.004</angularVelocityNoiseStdDev>
<rotorConfiguration>
<rotor>
<jointName>rotor_0_joint</jointName>
<forceConstant>8.54858e-06</forceConstant>
<momentConstant>0.016</momentConstant>
<direction>1</direction>
</rotor>
<rotor>
<jointName>rotor_1_joint</jointName>
<forceConstant>8.54858e-06</forceConstant>
<momentConstant>0.016</momentConstant>
<direction>1</direction>
</rotor>
<rotor>
<jointName>rotor_2_joint</jointName>
<forceConstant>8.54858e-06</forceConstant>
<momentConstant>0.016</momentConstant>
<direction>-1</direction>
</rotor>
<rotor>
<jointName>rotor_3_joint</jointName>
<forceConstant>8.54858e-06</forceConstant>
<momentConstant>0.016</momentConstant>
<direction>-1</direction>
</rotor>
</rotorConfiguration>
</plugin>
<!-- Battery plugin -->
<plugin filename="libignition-gazebo-linearbatteryplugin-system.so"
name="ignition::gazebo::systems::LinearBatteryPlugin">
<battery_name>linear_battery</battery_name>
<voltage>12.694</voltage>
<open_circuit_voltage_constant_coef>12.694</open_circuit_voltage_constant_coef>
<open_circuit_voltage_linear_coef>-3.1424</open_circuit_voltage_linear_coef>
<initial_charge>18.0</initial_charge>
<capacity>18.0</capacity>
<resistance>0.061523</resistance>
<smooth_current_tau>1.9499</smooth_current_tau>
<power_load>6.6</power_load>
<start_on_motion>true</start_on_motion>
</plugin>
<!-- Gas Sensor plugin -->
<plugin filename="libGasEmitterDetectorPlugin.so"
name="subt::GasDetector">
<topic>/model/#{_name}/gas_detected</topic>
<update_rate>10</update_rate>
<type>gas</type>
</plugin>
</include>
</sdf>
</spawn>
HEREDOC
exec = <<-HEREDOC
<executable name='x3_description'>
<command>roslaunch --wait subt_ros x3_description.launch world_name:=#{$worldName} name:=#{_name}</command>
</executable>
<executable name='x3_ros_ign_bridge'>
<command>roslaunch --wait subt_ros vehicle_topics.launch world_name:=#{$worldName} name:=#{_name} uav:=#{uav} laser_scan:=#{laserScan} stereo_cam:=#{stereoCam} rgbd_cam:=#{rgbdCam} breadcrumbs:=0</command>
</executable>
HEREDOC
return spawn, exec
end
def spawnX4(_name, _config, _x, _y, _z, _yaw)
uav=1
laserScan=0
stereoCam=0
rgbdCam=0
if _config == "2"
rgbdCam=1
end
if _config == "3" or _config == "4"
laserScan=1
end
if _config == "5"
stereoCam=1
end
z = _z + 0.125
spawn = <<-HEREDOC
<spawn name='#{_name}'>
<name>#{_name}</name>
<allow_renaming>false</allow_renaming>
<pose>#{_x} #{_y} #{z} 0 0 #{_yaw}</pose>
<world>#{$worldName}</world>
<is_performer>true</is_performer>
<sdf version='1.6'>
<include>
<name>#{_name}</name>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/X4 UAV Config #{_config}</uri>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>
<publish_sensor_pose>true</publish_sensor_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_nested_model_pose>#{$enableGroundTruth}</publish_nested_model_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
<static_publisher>true</static_publisher>
<static_update_frequency>1</static_update_frequency>
</plugin>
<plugin filename="libignition-gazebo-multicopter-motor-model-system.so"
name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>model/#{_name}</robotNamespace>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0182</timeConstantUp>
<timeConstantDown>0.0182</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>1.269e-05</motorConstant>
<momentConstant>0.016754</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>2.0673e-04</rotorDragCoefficient>
<rollingMomentCoefficient>0</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/0</motorSpeedPubTopic>