-
Notifications
You must be signed in to change notification settings - Fork 4.6k
/
AirSimSettings.hpp
1408 lines (1197 loc) · 67.5 KB
/
AirSimSettings.hpp
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
// Copyright (c) Microsoft Corporation. All rights reserved.
// Licensed under the MIT License.
#ifndef airsim_core_AirSimSettings_hpp
#define airsim_core_AirSimSettings_hpp
#include "CommonStructs.hpp"
#include "ImageCaptureBase.hpp"
#include "Settings.hpp"
#include "common_utils/Utils.hpp"
#include "sensors/SensorBase.hpp"
#include <exception>
#include <functional>
#include <map>
#include <string>
#include <vector>
namespace msr
{
namespace airlib
{
struct AirSimSettings
{
private:
typedef common_utils::Utils Utils;
typedef ImageCaptureBase::ImageType ImageType;
public: //types
static constexpr int kSubwindowCount = 3; //must be >= 3 for now
static constexpr char const* kVehicleTypePX4 = "px4multirotor";
static constexpr char const* kVehicleTypeArduCopterSolo = "arducoptersolo";
static constexpr char const* kVehicleTypeSimpleFlight = "simpleflight";
static constexpr char const* kVehicleTypeArduCopter = "arducopter";
static constexpr char const* kVehicleTypePhysXCar = "physxcar";
static constexpr char const* kVehicleTypeArduRover = "ardurover";
static constexpr char const* kVehicleTypeComputerVision = "computervision";
static constexpr char const* kVehicleInertialFrame = "VehicleInertialFrame";
static constexpr char const* kSensorLocalFrame = "SensorLocalFrame";
static constexpr char const* kSimModeTypeMultirotor = "Multirotor";
static constexpr char const* kSimModeTypeCar = "Car";
static constexpr char const* kSimModeTypeComputerVision = "ComputerVision";
struct SubwindowSetting
{
int window_index;
ImageType image_type;
bool visible;
std::string camera_name;
std::string vehicle_name;
bool external;
SubwindowSetting(int window_index_val = 0, ImageType image_type_val = ImageType::Scene, bool visible_val = false,
const std::string& camera_name_val = "", const std::string& vehicle_name_val = "", bool external_val = false)
: window_index(window_index_val)
, image_type(image_type_val)
, visible(visible_val)
, camera_name(camera_name_val)
, vehicle_name(vehicle_name_val)
, external(external_val)
{
}
};
struct RecordingSetting
{
bool record_on_move = false;
float record_interval = 0.05f;
std::string folder = "";
bool enabled = false;
std::map<std::string, std::vector<ImageCaptureBase::ImageRequest>> requests;
RecordingSetting()
{
}
RecordingSetting(bool record_on_move_val, float record_interval_val, const std::string& folder_val, bool enabled_val)
: record_on_move(record_on_move_val), record_interval(record_interval_val), folder(folder_val), enabled(enabled_val)
{
}
};
struct PawnPath
{
std::string pawn_bp;
std::string slippery_mat;
std::string non_slippery_mat;
PawnPath(const std::string& pawn_bp_val = "",
const std::string& slippery_mat_val = "/AirSim/VehicleAdv/PhysicsMaterials/Slippery.Slippery",
const std::string& non_slippery_mat_val = "/AirSim/VehicleAdv/PhysicsMaterials/NonSlippery.NonSlippery")
: pawn_bp(pawn_bp_val), slippery_mat(slippery_mat_val), non_slippery_mat(non_slippery_mat_val)
{
}
};
struct RCSettings
{
int remote_control_id = -1;
bool allow_api_when_disconnected = false;
};
struct Rotation
{
float yaw = 0;
float pitch = 0;
float roll = 0;
Rotation()
{
}
Rotation(float yaw_val, float pitch_val, float roll_val)
: yaw(yaw_val), pitch(pitch_val), roll(roll_val)
{
}
static Rotation nanRotation() noexcept
{
static const Rotation val(Utils::nan<float>(), Utils::nan<float>(), Utils::nan<float>());
return val;
}
};
struct GimbalSetting
{
float stabilization = 0;
//bool is_world_frame = false;
Rotation rotation = Rotation::nanRotation();
};
struct CaptureSetting
{
//below settings_json are obtained by using Unreal console command (press ~):
// ShowFlag.VisualizeHDR 1.
//to replicate camera settings_json to SceneCapture2D
//TODO: should we use UAirBlueprintLib::GetDisplayGamma()?
static constexpr float kSceneTargetGamma = 1.4f;
int image_type = 0;
unsigned int width = 256, height = 144; //960 X 540
float fov_degrees = Utils::nan<float>(); //90.0f
int auto_exposure_method = -1; //histogram
float auto_exposure_speed = Utils::nan<float>(); // 100.0f;
float auto_exposure_bias = Utils::nan<float>(); // 0;
float auto_exposure_max_brightness = Utils::nan<float>(); // 0.64f;
float auto_exposure_min_brightness = Utils::nan<float>(); // 0.03f;
float auto_exposure_low_percent = Utils::nan<float>(); // 80.0f;
float auto_exposure_high_percent = Utils::nan<float>(); // 98.3f;
float auto_exposure_histogram_log_min = Utils::nan<float>(); // -8;
float auto_exposure_histogram_log_max = Utils::nan<float>(); // 4;
float motion_blur_amount = Utils::nan<float>();
float target_gamma = Utils::nan<float>(); //1.0f; //This would be reset to kSceneTargetGamma for scene as default
int projection_mode = 0; // ECameraProjectionMode::Perspective
float ortho_width = Utils::nan<float>();
};
struct NoiseSetting
{
int ImageType = 0;
bool Enabled = false;
float RandContrib = 0.2f;
float RandSpeed = 100000.0f;
float RandSize = 500.0f;
float RandDensity = 2.0f;
float HorzWaveContrib = 0.03f;
float HorzWaveStrength = 0.08f;
float HorzWaveVertSize = 1.0f;
float HorzWaveScreenSize = 1.0f;
float HorzNoiseLinesContrib = 1.0f;
float HorzNoiseLinesDensityY = 0.01f;
float HorzNoiseLinesDensityXY = 0.5f;
float HorzDistortionContrib = 1.0f;
float HorzDistortionStrength = 0.002f;
};
struct PixelFormatOverrideSetting
{
int pixel_format = 0;
};
struct UnrealEngineSetting
{
std::map<int, PixelFormatOverrideSetting> pixel_format_override_settings;
};
using CaptureSettingsMap = std::map<int, CaptureSetting>;
using NoiseSettingsMap = std::map<int, NoiseSetting>;
struct CameraSetting
{
//nan means keep the default values set in components
Vector3r position = VectorMath::nanVector();
Rotation rotation = Rotation::nanRotation();
GimbalSetting gimbal;
CaptureSettingsMap capture_settings;
NoiseSettingsMap noise_settings;
UnrealEngineSetting ue_setting;
CameraSetting()
{
initializeCaptureSettings(capture_settings);
initializeNoiseSettings(noise_settings);
}
};
using CameraSettingMap = std::map<std::string, CameraSetting>;
struct CameraDirectorSetting
{
Vector3r position = VectorMath::nanVector();
Rotation rotation = Rotation::nanRotation();
float follow_distance = Utils::nan<float>();
};
struct SensorSetting
{
SensorBase::SensorType sensor_type;
std::string sensor_name;
bool enabled = true;
Settings settings; // imported json data that needs to be parsed by specific sensors.
};
struct BarometerSetting : SensorSetting
{
};
struct ImuSetting : SensorSetting
{
};
struct GpsSetting : SensorSetting
{
};
struct MagnetometerSetting : SensorSetting
{
};
struct DistanceSetting : SensorSetting
{
};
struct LidarSetting : SensorSetting
{
};
struct VehicleSetting
{
//required
std::string vehicle_name;
std::string vehicle_type;
//optional
std::string default_vehicle_state;
std::string pawn_path;
bool allow_api_always = true;
bool auto_create = true;
bool enable_collision_passthrough = false;
bool enable_trace = false;
bool enable_collisions = true;
bool is_fpv_vehicle = false;
//nan means use player start
Vector3r position = VectorMath::nanVector(); //in global NED
Rotation rotation = Rotation::nanRotation();
CameraSettingMap cameras;
std::map<std::string, std::shared_ptr<SensorSetting>> sensors;
RCSettings rc;
VehicleSetting()
{
}
VehicleSetting(const std::string& vehicle_name_val, const std::string& vehicle_type_val)
: vehicle_name(vehicle_name_val), vehicle_type(vehicle_type_val)
{
}
};
struct MavLinkConnectionInfo
{
/* Default values are requires so uninitialized instance doesn't have random values */
bool use_serial = true; // false means use UDP or TCP instead
//Used to connect via HITL: needed only if use_serial = true
std::string serial_port = "*";
int baud_rate = 115200;
// Used to connect to drone over UDP: needed only if use_serial = false and use_tcp == false
std::string udp_address = "127.0.0.1";
int udp_port = 14560;
// Used to accept connections from drone over TCP: needed only if use_tcp = true
bool lock_step = true;
bool use_tcp = false;
int tcp_port = 4560;
// The PX4 SITL app requires receiving drone commands over a different mavlink channel called
// the "ground control station" (or GCS) channel.
std::string control_ip_address = "127.0.0.1";
int control_port_local = 14540;
int control_port_remote = 14580;
// The log viewer can be on a different machine, so you can configure it's ip address and port here.
int logviewer_ip_port = 14388;
int logviewer_ip_sport = 14389; // for logging all messages we send to the vehicle.
std::string logviewer_ip_address = "";
// The QGroundControl app can be on a different machine, and AirSim can act as a proxy to forward
// the mavlink stream over to that machine if you configure it's ip address and port here.
int qgc_ip_port = 0;
std::string qgc_ip_address = "";
// mavlink vehicle identifiers
uint8_t sim_sysid = 142;
int sim_compid = 42;
uint8_t offboard_sysid = 134;
int offboard_compid = 1;
uint8_t vehicle_sysid = 135;
int vehicle_compid = 1;
// if you want to select a specific local network adapter so you can reach certain remote machines (e.g. wifi versus ethernet)
// then you will want to change the LocalHostIp accordingly. This default only works when log viewer and QGC are also on the
// same machine. Whatever network you choose it has to be the same one for external
std::string local_host_ip = "127.0.0.1";
std::string model = "Generic";
std::map<std::string, float> params;
std::string logs;
};
struct MavLinkVehicleSetting : public VehicleSetting
{
MavLinkConnectionInfo connection_info;
};
struct SegmentationSetting
{
enum class InitMethodType
{
None,
CommonObjectsRandomIDs
};
enum class MeshNamingMethodType
{
OwnerName,
StaticMeshName
};
InitMethodType init_method = InitMethodType::CommonObjectsRandomIDs;
bool override_existing = false;
MeshNamingMethodType mesh_naming_method = MeshNamingMethodType::OwnerName;
};
struct TimeOfDaySetting
{
bool enabled = false;
std::string start_datetime = ""; //format: %Y-%m-%d %H:%M:%S
bool is_start_datetime_dst = false;
float celestial_clock_speed = 1;
float update_interval_secs = 60;
bool move_sun = true;
};
private: //fields
float settings_version_actual;
float settings_version_minimum = 1.2f;
public: //fields
std::string simmode_name = "";
std::string level_name = "";
std::vector<SubwindowSetting> subwindow_settings;
RecordingSetting recording_setting;
SegmentationSetting segmentation_setting;
TimeOfDaySetting tod_setting;
std::vector<std::string> warning_messages;
std::vector<std::string> error_messages;
bool is_record_ui_visible = false;
int initial_view_mode = 2; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME
bool enable_rpc = true;
std::string api_server_address = "";
int api_port = RpcLibPort;
std::string physics_engine_name = "";
std::string clock_type = "";
float clock_speed = 1.0f;
bool engine_sound = false;
bool log_messages_visible = true;
bool show_los_debug_lines_ = false;
HomeGeoPoint origin_geopoint{ GeoPoint(47.641468, -122.140165, 122) }; //The geo-coordinate assigned to Unreal coordinate 0,0,0
std::map<std::string, PawnPath> pawn_paths; //path for pawn blueprint
std::map<std::string, std::unique_ptr<VehicleSetting>> vehicles;
CameraSetting camera_defaults;
CameraDirectorSetting camera_director;
float speed_unit_factor = 1.0f;
std::string speed_unit_label = "m\\s";
std::map<std::string, std::shared_ptr<SensorSetting>> sensor_defaults;
Vector3r wind = Vector3r::Zero();
CameraSettingMap external_cameras;
std::string settings_text_ = "";
public: //methods
static AirSimSettings& singleton()
{
static AirSimSettings instance;
return instance;
}
AirSimSettings()
{
initializeSubwindowSettings(subwindow_settings);
initializePawnPaths(pawn_paths);
}
//returns number of warnings
void load(std::function<std::string(void)> simmode_getter)
{
warning_messages.clear();
error_messages.clear();
const Settings& settings_json = Settings::singleton();
checkSettingsVersion(settings_json);
loadCoreSimModeSettings(settings_json, simmode_getter);
loadLevelSettings(settings_json);
loadDefaultCameraSetting(settings_json, camera_defaults);
loadCameraDirectorSetting(settings_json, camera_director, simmode_name);
loadSubWindowsSettings(settings_json, subwindow_settings);
loadViewModeSettings(settings_json);
loadSegmentationSetting(settings_json, segmentation_setting);
loadPawnPaths(settings_json, pawn_paths);
loadOtherSettings(settings_json);
loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults);
loadVehicleSettings(simmode_name, settings_json, vehicles, sensor_defaults, camera_defaults);
loadExternalCameraSettings(settings_json, external_cameras, camera_defaults);
//this should be done last because it depends on vehicles (and/or their type) we have
loadRecordingSetting(settings_json);
loadClockSettings(settings_json);
}
static void initializeSettings(const std::string& json_settings_text)
{
singleton().settings_text_ = json_settings_text;
Settings& settings_json = Settings::loadJSonString(json_settings_text);
if (!settings_json.isLoadSuccess())
throw std::invalid_argument("Cannot parse JSON settings_json string.");
}
static void createDefaultSettingsFile()
{
initializeSettings("{}");
Settings& settings_json = Settings::singleton();
//write some settings_json in new file otherwise the string "null" is written if all settings_json are empty
settings_json.setString("SeeDocsAt", "https://github.com/Microsoft/AirSim/blob/main/docs/settings.md");
settings_json.setDouble("SettingsVersion", 1.2);
std::string settings_filename = Settings::getUserDirectoryFullPath("settings.json");
//TODO: there is a crash in Linux due to settings_json.saveJSonString(). Remove this workaround after we only support Unreal 4.17
//https://answers.unrealengine.com/questions/664905/unreal-crashes-on-two-lines-of-extremely-simple-st.html
settings_json.saveJSonFile(settings_filename);
}
// This is for the case when a new vehicle is made on the fly, at runtime
void addVehicleSetting(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path = "")
{
// No Mavlink-type vehicles currently
auto vehicle_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting(vehicle_name, vehicle_type));
vehicle_setting->position = pose.position;
vehicle_setting->pawn_path = pawn_path;
vehicle_setting->sensors = sensor_defaults;
VectorMath::toEulerianAngle(pose.orientation, vehicle_setting->rotation.pitch, vehicle_setting->rotation.roll, vehicle_setting->rotation.yaw);
vehicles[vehicle_name] = std::move(vehicle_setting);
}
const VehicleSetting* getVehicleSetting(const std::string& vehicle_name) const
{
auto it = vehicles.find(vehicle_name);
if (it == vehicles.end())
// pre-existing flying pawns in Unreal Engine don't have name 'SimpleFlight'
it = vehicles.find("SimpleFlight");
return it->second.get();
}
static Vector3r createVectorSetting(const Settings& settings_json, const Vector3r& default_vec)
{
return Vector3r(settings_json.getFloat("X", default_vec.x()),
settings_json.getFloat("Y", default_vec.y()),
settings_json.getFloat("Z", default_vec.z()));
}
static Rotation createRotationSetting(const Settings& settings_json, const Rotation& default_rot)
{
return Rotation(settings_json.getFloat("Yaw", default_rot.yaw),
settings_json.getFloat("Pitch", default_rot.pitch),
settings_json.getFloat("Roll", default_rot.roll));
}
private:
void checkSettingsVersion(const Settings& settings_json)
{
bool has_default_settings = hasDefaultSettings(settings_json, settings_version_actual);
bool upgrade_required = settings_version_actual < settings_version_minimum;
if (upgrade_required) {
bool auto_upgrade = false;
//if we have default setting file not modified by user then we will
//just auto-upgrade it
if (has_default_settings) {
auto_upgrade = true;
}
else {
//check if auto-upgrade is possible
if (settings_version_actual == 1) {
const std::vector<std::string> all_changed_keys = {
"AdditionalCameras", "CaptureSettings", "NoiseSettings", "UsageScenario", "SimpleFlight", "PX4"
};
std::stringstream detected_keys_ss;
for (const auto& changed_key : all_changed_keys) {
if (settings_json.hasKey(changed_key))
detected_keys_ss << changed_key << ",";
}
std::string detected_keys = detected_keys_ss.str();
if (detected_keys.length()) {
std::string error_message =
"You are using newer version of AirSim with older version of settings.json. "
"You can either delete your settings.json and restart AirSim or use the upgrade "
"instructions at https://git.io/vjefh. \n\n"
"Following keys in your settings.json needs updating: ";
error_messages.push_back(error_message + detected_keys);
}
else
auto_upgrade = true;
}
else
auto_upgrade = true;
}
if (auto_upgrade) {
warning_messages.push_back(
"You are using newer version of AirSim with older version of settings.json. "
"You should delete your settings.json file and restart AirSim.");
}
}
//else no action necessary
}
bool hasDefaultSettings(const Settings& settings_json, float& version)
{
//if empty settings file
bool has_default = settings_json.size() == 0;
bool has_docs = settings_json.getString("SeeDocsAt", "") != "" || settings_json.getString("see_docs_at", "") != "";
//we had spelling mistake so we are currently supporting SettingsVersion or SettingdVersion :(
version = settings_json.getFloat("SettingsVersion", settings_json.getFloat("SettingdVersion", 0));
//If we have pre-V1 settings and only element is docs link
has_default |= settings_json.size() == 1 && has_docs;
//if we have V1 settings and only elements are docs link and version
has_default |= settings_json.size() == 2 && has_docs && version > 0;
return has_default;
}
void loadCoreSimModeSettings(const Settings& settings_json, std::function<std::string(void)> simmode_getter)
{
//get the simmode from user if not specified
simmode_name = settings_json.getString("SimMode", "");
if (simmode_name == "") {
if (simmode_getter)
simmode_name = simmode_getter();
else
throw std::invalid_argument("simmode_name is not expected empty in SimModeBase");
}
physics_engine_name = settings_json.getString("PhysicsEngineName", "");
if (physics_engine_name == "") {
if (simmode_name == kSimModeTypeMultirotor)
physics_engine_name = "FastPhysicsEngine";
else
physics_engine_name = "PhysX"; //this value is only informational for now
}
}
void loadLevelSettings(const Settings& settings_json)
{
level_name = settings_json.getString("Default Environment", "");
}
void loadViewModeSettings(const Settings& settings_json)
{
std::string view_mode_string = settings_json.getString("ViewMode", "");
if (view_mode_string == "") {
if (simmode_name == kSimModeTypeMultirotor)
view_mode_string = "FlyWithMe";
else if (simmode_name == kSimModeTypeComputerVision)
view_mode_string = "Fpv";
else
view_mode_string = "SpringArmChase";
}
if (view_mode_string == "Fpv")
initial_view_mode = 0; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FPV;
else if (view_mode_string == "GroundObserver")
initial_view_mode = 1; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_GROUND_OBSERVER;
else if (view_mode_string == "FlyWithMe")
initial_view_mode = 2; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME;
else if (view_mode_string == "Manual")
initial_view_mode = 3; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_MANUAL;
else if (view_mode_string == "SpringArmChase")
initial_view_mode = 4; // ECameraDirectorMode::CAMERA_DIRECTOR_MODE_SPRINGARM_CHASE;
else if (view_mode_string == "Backup")
initial_view_mode = 5; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_BACKUP;
else if (view_mode_string == "NoDisplay")
initial_view_mode = 6; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_NODISPLAY;
else if (view_mode_string == "Front")
initial_view_mode = 7; // ECameraDirectorMode::CAMREA_DIRECTOR_MODE_FRONT;
else
error_messages.push_back("ViewMode setting is not recognized: " + view_mode_string);
}
static void loadRCSetting(const std::string& simmode_name, const Settings& settings_json, RCSettings& rc_setting)
{
Settings rc_json;
if (settings_json.getChild("RC", rc_json)) {
rc_setting.remote_control_id = rc_json.getInt("RemoteControlID",
simmode_name == kSimModeTypeMultirotor ? 0 : -1);
rc_setting.allow_api_when_disconnected = rc_json.getBool("AllowAPIWhenDisconnected",
rc_setting.allow_api_when_disconnected);
}
}
static std::string getCameraName(const Settings& settings_json)
{
return settings_json.getString("CameraName",
//TODO: below exist only due to legacy reason and can be replaced by "" in future
std::to_string(settings_json.getInt("CameraID", 0)));
}
void loadDefaultRecordingSettings()
{
recording_setting.requests.clear();
// Add Scene image for each vehicle
for (const auto& vehicle : vehicles) {
recording_setting.requests[vehicle.first].push_back(ImageCaptureBase::ImageRequest(
"", ImageType::Scene, false, true));
}
}
void loadRecordingSetting(const Settings& settings_json)
{
loadDefaultRecordingSettings();
Settings recording_json;
if (settings_json.getChild("Recording", recording_json)) {
recording_setting.record_on_move = recording_json.getBool("RecordOnMove", recording_setting.record_on_move);
recording_setting.record_interval = recording_json.getFloat("RecordInterval", recording_setting.record_interval);
recording_setting.folder = recording_json.getString("Folder", recording_setting.folder);
recording_setting.enabled = recording_json.getBool("Enabled", recording_setting.enabled);
Settings req_cameras_settings;
if (recording_json.getChild("Cameras", req_cameras_settings)) {
// If 'Cameras' field is present, clear defaults
recording_setting.requests.clear();
// Get name of the default vehicle to be used if "VehicleName" isn't specified
// Map contains a default vehicle if vehicles haven't been specified
std::string default_vehicle_name = vehicles.begin()->first;
for (size_t child_index = 0; child_index < req_cameras_settings.size(); ++child_index) {
Settings req_camera_settings;
if (req_cameras_settings.getChild(child_index, req_camera_settings)) {
std::string camera_name = getCameraName(req_camera_settings);
ImageType image_type = Utils::toEnum<ImageType>(
req_camera_settings.getInt("ImageType", 0));
bool compress = req_camera_settings.getBool("Compress", true);
bool pixels_as_float = req_camera_settings.getBool("PixelsAsFloat", false);
std::string vehicle_name = req_camera_settings.getString("VehicleName", default_vehicle_name);
recording_setting.requests[vehicle_name].push_back(ImageCaptureBase::ImageRequest(
camera_name, image_type, pixels_as_float, compress));
}
}
}
}
}
static void initializeCaptureSettings(CaptureSettingsMap& capture_settings)
{
capture_settings.clear();
for (int i = -1; i < Utils::toNumeric(ImageType::Count); ++i) {
capture_settings[i] = CaptureSetting();
}
capture_settings.at(Utils::toNumeric(ImageType::Scene)).target_gamma = CaptureSetting::kSceneTargetGamma;
}
static void loadCaptureSettings(const Settings& settings_json, CaptureSettingsMap& capture_settings)
{
// We don't call initializeCaptureSettings here since it's already called in CameraSettings constructor
// And to avoid overwriting any defaults already set from CameraDefaults
Settings json_parent;
if (settings_json.getChild("CaptureSettings", json_parent)) {
for (size_t child_index = 0; child_index < json_parent.size(); ++child_index) {
Settings json_settings_child;
if (json_parent.getChild(child_index, json_settings_child)) {
CaptureSetting capture_setting;
createCaptureSettings(json_settings_child, capture_setting);
capture_settings[capture_setting.image_type] = capture_setting;
}
}
}
}
static std::unique_ptr<VehicleSetting> createMavLinkVehicleSetting(const Settings& settings_json)
{
//these settings_json are expected in same section, not in another child
std::unique_ptr<VehicleSetting> vehicle_setting_p = std::unique_ptr<VehicleSetting>(new MavLinkVehicleSetting());
MavLinkVehicleSetting* vehicle_setting = static_cast<MavLinkVehicleSetting*>(vehicle_setting_p.get());
//TODO: we should be selecting remote if available else keyboard
//currently keyboard is not supported so use rc as default
vehicle_setting->rc.remote_control_id = 0;
MavLinkConnectionInfo& connection_info = vehicle_setting->connection_info;
connection_info.sim_sysid = static_cast<uint8_t>(settings_json.getInt("SimSysID", connection_info.sim_sysid));
connection_info.sim_compid = settings_json.getInt("SimCompID", connection_info.sim_compid);
connection_info.vehicle_sysid = static_cast<uint8_t>(settings_json.getInt("VehicleSysID", connection_info.vehicle_sysid));
connection_info.vehicle_compid = settings_json.getInt("VehicleCompID", connection_info.vehicle_compid);
connection_info.offboard_sysid = static_cast<uint8_t>(settings_json.getInt("OffboardSysID", connection_info.offboard_sysid));
connection_info.offboard_compid = settings_json.getInt("OffboardCompID", connection_info.offboard_compid);
connection_info.logviewer_ip_address = settings_json.getString("LogViewerHostIp", connection_info.logviewer_ip_address);
connection_info.logviewer_ip_port = settings_json.getInt("LogViewerPort", connection_info.logviewer_ip_port);
connection_info.logviewer_ip_sport = settings_json.getInt("LogViewerSendPort", connection_info.logviewer_ip_sport);
connection_info.qgc_ip_address = settings_json.getString("QgcHostIp", connection_info.qgc_ip_address);
connection_info.qgc_ip_port = settings_json.getInt("QgcPort", connection_info.qgc_ip_port);
connection_info.control_ip_address = settings_json.getString("ControlIp", connection_info.control_ip_address);
connection_info.control_port_local = settings_json.getInt("ControlPort", connection_info.control_port_local); // legacy
connection_info.control_port_local = settings_json.getInt("ControlPortLocal", connection_info.control_port_local);
connection_info.control_port_remote = settings_json.getInt("ControlPortRemote", connection_info.control_port_remote);
std::string sitlip = settings_json.getString("SitlIp", connection_info.control_ip_address);
if (sitlip.size() > 0 && connection_info.control_ip_address.size() == 0) {
// backwards compat
connection_info.control_ip_address = sitlip;
}
if (settings_json.hasKey("SitlPort")) {
// backwards compat
connection_info.control_port_local = settings_json.getInt("SitlPort", connection_info.control_port_local);
}
connection_info.local_host_ip = settings_json.getString("LocalHostIp", connection_info.local_host_ip);
connection_info.use_serial = settings_json.getBool("UseSerial", connection_info.use_serial);
connection_info.udp_address = settings_json.getString("UdpIp", connection_info.udp_address);
connection_info.udp_port = settings_json.getInt("UdpPort", connection_info.udp_port);
connection_info.use_tcp = settings_json.getBool("UseTcp", connection_info.use_tcp);
connection_info.lock_step = settings_json.getBool("LockStep", connection_info.lock_step);
connection_info.tcp_port = settings_json.getInt("TcpPort", connection_info.tcp_port);
connection_info.serial_port = settings_json.getString("SerialPort", connection_info.serial_port);
connection_info.baud_rate = settings_json.getInt("SerialBaudRate", connection_info.baud_rate);
connection_info.model = settings_json.getString("Model", connection_info.model);
connection_info.logs = settings_json.getString("Logs", connection_info.logs);
Settings params;
if (settings_json.getChild("Parameters", params)) {
std::vector<std::string> keys;
params.getChildNames(keys);
for (auto key : keys) {
connection_info.params[key] = params.getFloat(key, 0);
}
}
return vehicle_setting_p;
}
static std::unique_ptr<VehicleSetting> createVehicleSetting(const std::string& simmode_name, const Settings& settings_json,
const std::string vehicle_name,
std::map<std::string, std::shared_ptr<SensorSetting>>& sensor_defaults,
const CameraSetting& camera_defaults)
{
auto vehicle_type = Utils::toLower(settings_json.getString("VehicleType", ""));
std::unique_ptr<VehicleSetting> vehicle_setting;
if (vehicle_type == kVehicleTypePX4 || vehicle_type == kVehicleTypeArduCopterSolo || vehicle_type == kVehicleTypeArduCopter || vehicle_type == kVehicleTypeArduRover)
vehicle_setting = createMavLinkVehicleSetting(settings_json);
//for everything else we don't need derived class yet
else {
vehicle_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
if (vehicle_type == kVehicleTypeSimpleFlight) {
//TODO: we should be selecting remote if available else keyboard
//currently keyboard is not supported so use rc as default
vehicle_setting->rc.remote_control_id = 0;
}
}
vehicle_setting->vehicle_name = vehicle_name;
//required settings_json
vehicle_setting->vehicle_type = vehicle_type;
//optional settings_json
vehicle_setting->pawn_path = settings_json.getString("PawnPath", "");
vehicle_setting->default_vehicle_state = settings_json.getString("DefaultVehicleState", "");
vehicle_setting->allow_api_always = settings_json.getBool("AllowAPIAlways",
vehicle_setting->allow_api_always);
vehicle_setting->auto_create = settings_json.getBool("AutoCreate",
vehicle_setting->auto_create);
vehicle_setting->enable_collision_passthrough = settings_json.getBool("EnableCollisionPassthrogh",
vehicle_setting->enable_collision_passthrough);
vehicle_setting->enable_trace = settings_json.getBool("EnableTrace",
vehicle_setting->enable_trace);
vehicle_setting->enable_collisions = settings_json.getBool("EnableCollisions",
vehicle_setting->enable_collisions);
vehicle_setting->is_fpv_vehicle = settings_json.getBool("IsFpvVehicle",
vehicle_setting->is_fpv_vehicle);
loadRCSetting(simmode_name, settings_json, vehicle_setting->rc);
vehicle_setting->position = createVectorSetting(settings_json, vehicle_setting->position);
vehicle_setting->rotation = createRotationSetting(settings_json, vehicle_setting->rotation);
loadCameraSettings(settings_json, vehicle_setting->cameras, camera_defaults);
loadSensorSettings(settings_json, "Sensors", vehicle_setting->sensors, sensor_defaults);
return vehicle_setting;
}
static void createDefaultVehicle(const std::string& simmode_name, std::map<std::string, std::unique_ptr<VehicleSetting>>& vehicles,
const std::map<std::string, std::shared_ptr<SensorSetting>>& sensor_defaults)
{
vehicles.clear();
//NOTE: Do not set defaults for vehicle type here. If you do then make sure
//to sync code in createVehicleSetting() as well.
if (simmode_name == kSimModeTypeMultirotor) {
// create simple flight as default multirotor
auto simple_flight_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting("SimpleFlight",
kVehicleTypeSimpleFlight));
// TODO: we should be selecting remote if available else keyboard
// currently keyboard is not supported so use rc as default
simple_flight_setting->rc.remote_control_id = 0;
simple_flight_setting->sensors = sensor_defaults;
vehicles[simple_flight_setting->vehicle_name] = std::move(simple_flight_setting);
}
else if (simmode_name == kSimModeTypeCar) {
// create PhysX as default car vehicle
auto physx_car_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting("PhysXCar", kVehicleTypePhysXCar));
physx_car_setting->sensors = sensor_defaults;
vehicles[physx_car_setting->vehicle_name] = std::move(physx_car_setting);
}
else if (simmode_name == kSimModeTypeComputerVision) {
// create default computer vision vehicle
auto cv_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting("ComputerVision", kVehicleTypeComputerVision));
cv_setting->sensors = sensor_defaults;
vehicles[cv_setting->vehicle_name] = std::move(cv_setting);
}
else {
throw std::invalid_argument(Utils::stringf(
"Unknown SimMode: %s, failed to set default vehicle settings", simmode_name.c_str())
.c_str());
}
}
static void loadVehicleSettings(const std::string& simmode_name, const Settings& settings_json,
std::map<std::string, std::unique_ptr<VehicleSetting>>& vehicles,
std::map<std::string, std::shared_ptr<SensorSetting>>& sensor_defaults,
const CameraSetting& camera_defaults)
{
createDefaultVehicle(simmode_name, vehicles, sensor_defaults);
msr::airlib::Settings vehicles_child;
if (settings_json.getChild("Vehicles", vehicles_child)) {
std::vector<std::string> keys;
vehicles_child.getChildNames(keys);
//remove default vehicles, if values are specified in settings
if (keys.size())
vehicles.clear();
for (const auto& key : keys) {
msr::airlib::Settings child;
vehicles_child.getChild(key, child);
vehicles[key] = createVehicleSetting(simmode_name, child, key, sensor_defaults, camera_defaults);
}
}
}
static void initializePawnPaths(std::map<std::string, PawnPath>& pawn_paths)
{
pawn_paths.clear();
pawn_paths.emplace("BareboneCar",
PawnPath("Class'/AirSim/VehicleAdv/Vehicle/VehicleAdvPawn.VehicleAdvPawn_C'"));
pawn_paths.emplace("DefaultCar",
PawnPath("Class'/AirSim/VehicleAdv/SUV/SuvCarPawn.SuvCarPawn_C'"));
pawn_paths.emplace("DefaultQuadrotor",
PawnPath("Class'/AirSim/Blueprints/BP_FlyingPawn.BP_FlyingPawn_C'"));
pawn_paths.emplace("DefaultComputerVision",
PawnPath("Class'/AirSim/Blueprints/BP_ComputerVisionPawn.BP_ComputerVisionPawn_C'"));
}
static void loadPawnPaths(const Settings& settings_json, std::map<std::string, PawnPath>& pawn_paths)
{
initializePawnPaths(pawn_paths);
msr::airlib::Settings pawn_paths_child;
if (settings_json.getChild("PawnPaths", pawn_paths_child)) {
std::vector<std::string> keys;
pawn_paths_child.getChildNames(keys);
for (const auto& key : keys) {
msr::airlib::Settings child;
pawn_paths_child.getChild(key, child);
pawn_paths[key] = createPathPawn(child);
}
}
}
static PawnPath createPathPawn(const Settings& settings_json)
{
auto paths = PawnPath();
paths.pawn_bp = settings_json.getString("PawnBP", "");
auto slippery_mat = settings_json.getString("SlipperyMat", "");
auto non_slippery_mat = settings_json.getString("NonSlipperyMat", "");
if (slippery_mat != "")
paths.slippery_mat = slippery_mat;
if (non_slippery_mat != "")
paths.non_slippery_mat = non_slippery_mat;
return paths;
}
static void loadSegmentationSetting(const Settings& settings_json, SegmentationSetting& segmentation_setting)
{
Settings json_parent;
if (settings_json.getChild("SegmentationSettings", json_parent)) {
std::string init_method = Utils::toLower(json_parent.getString("InitMethod", ""));
if (init_method == "" || init_method == "commonobjectsrandomids")
segmentation_setting.init_method = SegmentationSetting::InitMethodType::CommonObjectsRandomIDs;
else if (init_method == "none")
segmentation_setting.init_method = SegmentationSetting::InitMethodType::None;
else
//TODO: below exception doesn't actually get raised right now because of issue in Unreal Engine?
throw std::invalid_argument(std::string("SegmentationSetting init_method has invalid value in settings_json ") + init_method);
segmentation_setting.override_existing = json_parent.getBool("OverrideExisting", true);
std::string mesh_naming_method = Utils::toLower(json_parent.getString("MeshNamingMethod", ""));
if (mesh_naming_method == "" || mesh_naming_method == "ownername")
segmentation_setting.mesh_naming_method = SegmentationSetting::MeshNamingMethodType::OwnerName;
else if (mesh_naming_method == "staticmeshname")
segmentation_setting.mesh_naming_method = SegmentationSetting::MeshNamingMethodType::StaticMeshName;
else
throw std::invalid_argument(std::string("SegmentationSetting MeshNamingMethod has invalid value in settings_json ") + mesh_naming_method);
}
}
static void initializeNoiseSettings(NoiseSettingsMap& noise_settings)
{
const int image_count = Utils::toNumeric(ImageType::Count);
noise_settings.clear();
for (int i = -1; i < image_count; ++i)
noise_settings[i] = NoiseSetting();
}
static void loadNoiseSettings(const Settings& settings_json, NoiseSettingsMap& noise_settings)
{
// We don't call initializeNoiseSettings here since it's already called in CameraSettings constructor
// And to avoid overwriting any defaults already set from CameraDefaults
Settings json_parent;