forked from allenai/ai2thor
-
Notifications
You must be signed in to change notification settings - Fork 0
/
AgentManager.cs
2104 lines (1772 loc) · 78.4 KB
/
AgentManager.cs
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
using System;
using System.Collections;
using System.Collections.Generic;
using UnityEngine;
using UnityStandardAssets.Characters.FirstPerson;
using System.IO;
using System.Net.Sockets;
using System.Net;
using MessagePack.Resolvers;
using MessagePack.Formatters;
using MessagePack;
using Newtonsoft.Json;
using Newtonsoft.Json.Linq;
using Newtonsoft.Json.Serialization;
using System.Reflection;
using System.Text;
using UnityEngine.Rendering;
using UnityEngine.Experimental.Rendering;
#if PLATFORM_CLOUD_RENDERING
using Unity.Simulation;
using UnityEditor;
using UnityEngine.CloudRendering;
#endif
using UnityEngine.Networking;
using System.Linq;
using UnityEngine.Rendering.PostProcessing;
using UnityStandardAssets.ImageEffects;
public class AgentManager : MonoBehaviour {
public List<BaseFPSAgentController> agents = new List<BaseFPSAgentController>();
protected int frameCounter;
protected bool serverSideScreenshot;
protected string robosimsClientToken = "";
protected int robosimsPort = 8200;
protected string robosimsHost = "127.0.0.1";
protected string ENVIRONMENT_PREFIX = "AI2THOR_";
public Texture2D tex;
public Rect readPixelsRect;
private int currentSequenceId;
private int activeAgentId;
private bool renderImage = true;
private bool renderDepthImage;
private bool renderSemanticSegmentation;
private bool renderInstanceSegmentation;
private bool initializedInstanceSeg;
private bool renderNormalsImage;
private bool renderFlowImage;
private Socket sock = null;
[SerializeField]
public List<Camera> thirdPartyCameras = new List<Camera>();
private Color[] agentColors = new Color[] { Color.blue, Color.yellow, Color.green, Color.red, Color.magenta, Color.grey };
public int actionDuration = 3;
public BaseFPSAgentController primaryAgent;
private PhysicsSceneManager physicsSceneManager;
private FifoServer.Client fifoClient = null;
private enum serverTypes { WSGI, FIFO };
private serverTypes serverType;
private AgentState agentManagerState = AgentState.Emit;
private bool fastActionEmit = true;
// it is public to be accessible from the debug input field.
public HashSet<string> agentManagerActions = new HashSet<string> { "Reset", "Initialize", "AddThirdPartyCamera", "UpdateThirdPartyCamera", "ChangeResolution", "CoordinateFromRaycastThirdPartyCamera", "ChangeQuality" };
public bool doResetMaterials = false;
public bool doResetColors = false;
public const float DEFAULT_FOV = 90;
public const float MAX_FOV = 180;
public const float MIN_FOV = 0;
public string agentMode;
public Bounds sceneBounds = UtilityFunctions.CreateEmptyBounds();
public Bounds SceneBounds {
get {
if (sceneBounds.min.x == float.PositiveInfinity) {
ResetSceneBounds();
}
return sceneBounds;
}
set {
sceneBounds = value;
}
}
void Awake() {
tex = new Texture2D(UnityEngine.Screen.width, UnityEngine.Screen.height, TextureFormat.RGB24, false);
readPixelsRect = new Rect(0, 0, UnityEngine.Screen.width, UnityEngine.Screen.height);
#if !UNITY_WEBGL
// Creates warning for WebGL
// https://forum.unity.com/threads/rendering-without-using-requestanimationframe-for-the-main-loop.373331/
Application.targetFrameRate = 3000;
#else
Debug.unityLogger.logEnabled = Debug.isDebugBuild;
#endif
QualitySettings.vSyncCount = 0;
robosimsPort = LoadIntVariable(robosimsPort, "PORT");
robosimsHost = LoadStringVariable(robosimsHost, "HOST");
serverSideScreenshot = LoadBoolVariable(serverSideScreenshot, "SERVER_SIDE_SCREENSHOT");
robosimsClientToken = LoadStringVariable(robosimsClientToken, "CLIENT_TOKEN");
serverType = (serverTypes)Enum.Parse(typeof(serverTypes), LoadStringVariable(serverTypes.WSGI.ToString(), "SERVER_TYPE").ToUpper());
if (serverType == serverTypes.FIFO) {
string serverPipePath = LoadStringVariable(null, "FIFO_SERVER_PIPE_PATH");
string clientPipePath = LoadStringVariable(null, "FIFO_CLIENT_PIPE_PATH");
Debug.Log("creating fifo server: " + serverPipePath);
Debug.Log("client fifo path: " + clientPipePath);
this.fifoClient = FifoServer.Client.GetInstance(serverPipePath, clientPipePath);
}
bool trainPhase = true;
trainPhase = LoadBoolVariable(trainPhase, "TRAIN_PHASE");
// read additional configurations for model
// agent speed and action length
string prefix = trainPhase ? "TRAIN_" : "TEST_";
actionDuration = LoadIntVariable(actionDuration, prefix + "ACTION_LENGTH");
}
void Start() {
// default primary agent's agentController type to "PhysicsRemoteFPSAgentController"
initializePrimaryAgent();
#if PLATFORM_CLOUD_RENDERING
// must wrap this in PLATFORM_CLOUDRENDERING
// needed to ensure that the com.unity.simulation.capture package
// gets initialized
var instance = Manager.Instance;
Camera camera = this.primaryAgent.gameObject.GetComponentInChildren<Camera>();
camera.targetTexture = createRenderTexture(Screen.width, Screen.height);
#endif
primaryAgent.actionDuration = this.actionDuration;
// this.agents.Add (primaryAgent);
physicsSceneManager = GameObject.Find("PhysicsSceneManager").GetComponent<PhysicsSceneManager>();
// auto set agentMode to default for the web demo
#if UNITY_WEBGL
physicsSceneManager.UnpausePhysicsAutoSim();
primaryAgent.InitializeBody(null);
JavaScriptInterface jsInterface = primaryAgent.GetComponent<JavaScriptInterface>();
if (jsInterface != null) {
jsInterface.enabled = true;
}
#endif
StartCoroutine(EmitFrame());
}
private void initializePrimaryAgent() {
if (this.PrimaryAgent == null) {
SetUpPhysicsController();
}
}
public void Initialize(ServerAction action) {
this.agentMode = action.agentMode.ToLower();
// first parse agentMode and agentControllerType
//"default" agentMode can use either default or "stochastic" agentControllerType
//"locobot" agentMode can use either default or "stochastic" agentControllerType
//"drone" agentMode can ONLY use "drone" agentControllerType, and NOTHING ELSE (for now?)
if (action.agentMode.ToLower() == "default") {
SetUpPhysicsController();
} else if (action.agentMode.ToLower() == "locobot") {
// LocobotController is a subclass of Stochastic which just the agentMode (VisibilityCapsule) changed
SetUpLocobotController(action);
} else if (action.agentMode.ToLower() == "drone") {
SetUpDroneController(action);
} else if (agentMode == "stretch" || agentMode == "arm") {
if (agentMode == "stretch") {
SetUpStretchController(action);
} else if (agentMode == "arm") {
SetUpArmController(true);
} else {
// Should not be possible but being very defensive.
throw new ArgumentException($"Invalid agentMode {action.agentMode}");
}
action.autoSimulation = false;
physicsSceneManager.MakeAllObjectsMoveable();
} else {
var error = $"Invalid agentMode {action.agentMode}";
Debug.Log(error);
primaryAgent.actionFinished(success: false, errorMessage: error);
return;
}
if (action.massThreshold.HasValue) {
if (action.massThreshold.Value > 0.0) {
SetUpMassThreshold(action.massThreshold.Value);
} else {
var error = $"massThreshold must have nonzero value - invalid value: {action.massThreshold.Value}";
Debug.Log(error);
primaryAgent.actionFinished(false, error);
return;
}
}
//initialize primary agent now that its controller component has been added
primaryAgent.ProcessControlCommand(action.dynamicServerAction);
Time.fixedDeltaTime = action.fixedDeltaTime.GetValueOrDefault(Time.fixedDeltaTime);
if (action.targetFrameRate > 0) {
Application.targetFrameRate = action.targetFrameRate;
}
primaryAgent.IsVisible = action.makeAgentsVisible;
this.renderSemanticSegmentation = action.renderSemanticSegmentation;
this.renderDepthImage = action.renderDepthImage;
this.renderNormalsImage = action.renderNormalsImage;
this.renderInstanceSegmentation = this.initializedInstanceSeg = action.renderInstanceSegmentation;
this.renderFlowImage = action.renderFlowImage;
this.fastActionEmit = action.fastActionEmit;
// we default Physics.autoSimulation to False in the built Player, but
// set ServerAction.autoSimulation = True for backwards compatibility. Keeping
// this value False allows the user complete control of all Physics Simulation
// if they need deterministic simulations.
Physics.autoSimulation = action.autoSimulation;
Physics.autoSyncTransforms = Physics.autoSimulation;
if (action.alwaysReturnVisibleRange) {
((PhysicsRemoteFPSAgentController)primaryAgent).alwaysReturnVisibleRange = action.alwaysReturnVisibleRange;
}
//if multi agent requested, add duplicates of primary agent now
addAgents(action);
this.agents[0].m_Camera.depth = 9999;
if (action.startAgentsRotatedBy != 0f) {
RotateAgentsByRotatingUniverse(action.startAgentsRotatedBy);
} else {
ResetSceneBounds();
}
this.agentManagerState = AgentState.ActionComplete;
}
private void SetUpLocobotController(ServerAction action) {
this.agents.Clear();
// force snapToGrid to be false since we are stochastic
action.snapToGrid = false;
BaseAgentComponent baseAgentComponent = GameObject.FindObjectOfType<BaseAgentComponent>();
primaryAgent = createAgentType(typeof(LocobotFPSAgentController), baseAgentComponent);
}
private void SetUpDroneController(ServerAction action) {
this.agents.Clear();
// force snapToGrid to be false
action.snapToGrid = false;
BaseAgentComponent baseAgentComponent = GameObject.FindObjectOfType<BaseAgentComponent>();
primaryAgent = createAgentType(typeof(DroneFPSAgentController), baseAgentComponent);
}
private void SetUpStretchController(ServerAction action) {
this.agents.Clear();
// force snapToGrid to be false
action.snapToGrid = false;
BaseAgentComponent baseAgentComponent = GameObject.FindObjectOfType<BaseAgentComponent>();
primaryAgent = createAgentType(typeof(StretchAgentController), baseAgentComponent);
}
// note: this doesn't take a ServerAction because we don't have to force the snpToGrid bool
// to be false like in other controller types.
public void SetUpPhysicsController() {
this.agents.Clear();
BaseAgentComponent baseAgentComponent = GameObject.FindObjectOfType<BaseAgentComponent>();
primaryAgent = createAgentType(typeof(PhysicsRemoteFPSAgentController), baseAgentComponent);
}
private BaseFPSAgentController createAgentType(Type agentType, BaseAgentComponent agentComponent) {
BaseFPSAgentController agent = Activator.CreateInstance(agentType, new object[] { agentComponent, this }) as BaseFPSAgentController;
this.agents.Add(agent);
return agent;
}
private void SetUpArmController(bool midLevelArm) {
this.agents.Clear();
BaseAgentComponent baseAgentComponent = GameObject.FindObjectOfType<BaseAgentComponent>();
primaryAgent = createAgentType(typeof(ArmAgentController), baseAgentComponent);
var handObj = primaryAgent.transform.FirstChildOrDefault((x) => x.name == "robot_arm_rig_gripper");
handObj.gameObject.SetActive(true);
}
// on initialization of agentMode = "arm" and agentControllerType = "mid-level"
// if mass threshold should be used to prevent arm from knocking over objects that
// are too big (table, sofa, shelf, etc) use this
private void SetUpMassThreshold(float massThreshold) {
CollisionListener.useMassThreshold = true;
CollisionListener.massThreshold = massThreshold;
primaryAgent.MakeObjectsStaticKinematicMassThreshold();
}
// return reference to primary agent in case we need a reference to the primary
public BaseFPSAgentController PrimaryAgent {
get => this.primaryAgent;
}
private void addAgents(ServerAction action) {
if (action.agentCount > 1) {
// note: for procedural scenes, adding multiple agents in will need to be done differently as currently
// initializing additional agents assumes the scene is already setup, and Houses initialize the
// primary agent floating in space, then generates the house, then teleports the primary agent.
// this will need a rework to make multi agent work as GetReachablePositions is used to position additional
// agents, which won't work if we initialize the agent(s) before the scene exists
if (UnityEngine.SceneManagement.SceneManager.GetActiveScene().name.StartsWith("Procedural")) {
throw new NotImplementedException($"Procedural scenes only support a single agent currently.");
}
Physics.SyncTransforms();
Vector3[] reachablePositions = primaryAgent.getReachablePositions(2.0f);
for (int i = 1; i < action.agentCount && this.agents.Count < Math.Min(agentColors.Length, action.agentCount); i++) {
action.x = reachablePositions[i + 4].x;
action.y = reachablePositions[i + 4].y;
action.z = reachablePositions[i + 4].z;
addAgent(action);
Physics.SyncTransforms(); // must do this so that when we CapsuleCast we see the most recently added agent
}
for (int i = 1; i < this.agents.Count; i++) {
this.agents[i].m_Camera.depth = 1;
}
}
}
public void ResetSceneBounds() {
// Recording initially disabled renderers and scene bounds
sceneBounds = UtilityFunctions.CreateEmptyBounds();
foreach (Renderer r in GameObject.FindObjectsOfType<Renderer>()) {
if (r.enabled) {
sceneBounds.Encapsulate(r.bounds);
}
}
}
public void RotateAgentsByRotatingUniverse(float rotation) {
List<Quaternion> startAgentRots = new List<Quaternion>();
foreach (BaseFPSAgentController agent in this.agents) {
startAgentRots.Add(agent.transform.rotation);
}
GameObject superObject = GameObject.Find("SuperTopLevel");
if (superObject == null) {
superObject = new GameObject("SuperTopLevel");
}
superObject.transform.position = this.agents[0].transform.position;
List<GameObject> topLevelObjects = new List<GameObject>();
foreach (GameObject go in UnityEngine.SceneManagement.SceneManager.GetActiveScene().GetRootGameObjects()) {
topLevelObjects.Add(go);
go.transform.SetParent(superObject.transform);
}
superObject.transform.rotation = Quaternion.Euler(0f, rotation, 0f);
foreach (GameObject go in topLevelObjects) {
go.transform.SetParent(null);
}
for (int i = 0; i < this.agents.Count; i++) {
agents[i].transform.rotation = startAgentRots[i];
}
ResetSceneBounds();
}
public void registerAsThirdPartyCamera(Camera camera) {
this.thirdPartyCameras.Add(camera);
#if PLATFORM_CLOUD_RENDERING
camera.targetTexture = createRenderTexture(this.primaryAgent.m_Camera.pixelWidth, this.primaryAgent.m_Camera.targetTexture.height);
#endif
}
// If fov is <= min or > max, return defaultVal, else return fov
private float ClampFieldOfView(float fov, float defaultVal = 90f, float min = 0f, float max = 180f) {
return (fov <= min || fov > max) ? defaultVal : fov;
}
public void updateImageSynthesis(bool status) {
foreach (var agent in this.agents) {
agent.updateImageSynthesis(status);
}
}
public void updateThirdPartyCameraImageSynthesis(bool status) {
if (status) {
foreach (var camera in this.thirdPartyCameras) {
GameObject gameObject = camera.gameObject;
var imageSynthesis = gameObject.GetComponentInChildren<ImageSynthesis>() as ImageSynthesis;
if (imageSynthesis == null) {
gameObject.AddComponent(typeof(ImageSynthesis));
}
imageSynthesis = gameObject.GetComponentInChildren<ImageSynthesis>() as ImageSynthesis;
imageSynthesis.enabled = status;
}
}
}
private void updateCameraProperties(
Camera camera,
Vector3 position,
Vector3 rotation,
float fieldOfView,
string skyboxColor,
bool? orthographic,
float? orthographicSize,
float? nearClippingPlane,
float? farClippingPlane
) {
if (orthographic != true && orthographicSize != null) {
throw new InvalidOperationException(
$"orthographicSize(: {orthographicSize}) can only be set when orthographic=True.\n" +
"Otherwise, we use assume perspective camera setting." +
"Hint: call .step(..., orthographic=True)."
);
}
// update the position and rotation
camera.gameObject.transform.position = position;
camera.gameObject.transform.eulerAngles = rotation;
// updates the camera's perspective
camera.fieldOfView = fieldOfView;
if (orthographic != null) {
camera.orthographic = (bool)orthographic;
if (orthographic == true && orthographicSize != null) {
camera.orthographicSize = (float)orthographicSize;
}
}
//updates camera near and far clipping planes
//default to near and far clipping planes of agent camera, which are currently
//static values and are not exposed in anything like Initialize
if (nearClippingPlane != null) {
camera.nearClipPlane = (float)nearClippingPlane;
}
//default to primary agent's near clip plane value
else {
camera.nearClipPlane = this.primaryAgent.m_Camera.nearClipPlane;
}
if (farClippingPlane != null) {
camera.farClipPlane = (float)farClippingPlane;
}
//default to primary agent's far clip plane value
else {
camera.farClipPlane = this.primaryAgent.m_Camera.farClipPlane;
}
// supports a solid color skybox, which work well with videos and images (i.e., white/black/orange/blue backgrounds)
if (skyboxColor == "default") {
camera.clearFlags = CameraClearFlags.Skybox;
} else if (skyboxColor != null) {
Color color;
bool successfullyParsed = ColorUtility.TryParseHtmlString(skyboxColor, out color);
if (successfullyParsed) {
camera.clearFlags = CameraClearFlags.SolidColor;
camera.backgroundColor = color;
} else {
throw new ArgumentException($"Invalid skyboxColor: {skyboxColor}! Cannot be parsed as an HTML color.");
}
}
this.activeAgent().actionFinished(success: true);
}
private void assertFovInBounds(float fov) {
if (fov <= MIN_FOV || fov >= MAX_FOV) {
throw new ArgumentOutOfRangeException($"fieldOfView: {fov} must be in {MIN_FOV} < fieldOfView > {MIN_FOV}.");
}
}
public void AddThirdPartyCamera(
Vector3 position,
Vector3 rotation,
float fieldOfView = DEFAULT_FOV,
string skyboxColor = null,
bool orthographic = false,
float? orthographicSize = null,
float? nearClippingPlane = null,
float? farClippingPlane = null,
string antiAliasing = "none"
) {
// adds error if fieldOfView is out of bounds
assertFovInBounds(fov: fieldOfView);
GameObject gameObject = GameObject.Instantiate(Resources.Load("ThirdPartyCameraTemplate")) as GameObject;
gameObject.name = "ThirdPartyCamera" + thirdPartyCameras.Count;
Camera camera = gameObject.GetComponentInChildren<Camera>();
// set up returned image
camera.cullingMask = ~LayerMask.GetMask("PlaceableSurface");
if (renderDepthImage || renderSemanticSegmentation || renderInstanceSegmentation || renderNormalsImage || renderFlowImage) {
gameObject.AddComponent(typeof(ImageSynthesis));
}
#if PLATFORM_CLOUD_RENDERING
camera.targetTexture = createRenderTexture(this.primaryAgent.m_Camera.pixelWidth, this.primaryAgent.m_Camera.targetTexture.height);
#endif
antiAliasing = antiAliasing.ToLower();
PostProcessLayer postProcessLayer = gameObject.GetComponentInChildren<PostProcessLayer>();
if (antiAliasing == "none") {
postProcessLayer.enabled = false;
} else {
postProcessLayer.enabled = true;
switch (antiAliasing) {
case "fxaa":
postProcessLayer.antialiasingMode = PostProcessLayer.Antialiasing.FastApproximateAntialiasing;
break;
case "smaa":
postProcessLayer.antialiasingMode = PostProcessLayer.Antialiasing.SubpixelMorphologicalAntialiasing;
break;
case "taa":
postProcessLayer.antialiasingMode = PostProcessLayer.Antialiasing.TemporalAntialiasing;
break;
default:
break;
}
}
thirdPartyCameras.Add(camera);
updateCameraProperties(
camera: camera,
position: position,
rotation: rotation,
fieldOfView: fieldOfView,
skyboxColor: skyboxColor,
orthographic: orthographic,
orthographicSize: orthographicSize,
nearClippingPlane: nearClippingPlane,
farClippingPlane: farClippingPlane
);
}
// helper that can be used when converting Dictionary<string, float> to a Vector3.
private Vector3 parseOptionalVector3(
OptionalVector3 optionalVector3,
Vector3 defaultsOnNull
) {
if (optionalVector3 == null) {
return defaultsOnNull;
}
return new Vector3(
x: optionalVector3.x == null ? defaultsOnNull.x : (float)optionalVector3.x,
y: optionalVector3.y == null ? defaultsOnNull.y : (float)optionalVector3.y,
z: optionalVector3.z == null ? defaultsOnNull.z : (float)optionalVector3.z
);
}
// Here, we don't want some dimensions set. For instance, set x, but not y.
public class OptionalVector3 {
public float? x = null;
public float? y = null;
public float? z = null;
}
// note that using a using a Dictionary<string, float> allows for only x, y, or z
// to be passed in, individually, whereas using Vector3 would require each of x/y/z.
public void UpdateThirdPartyCamera(
int thirdPartyCameraId = 0,
OptionalVector3 position = null,
OptionalVector3 rotation = null,
float? fieldOfView = null,
string skyboxColor = null,
bool? orthographic = null,
float? orthographicSize = null,
float? nearClippingPlane = null,
float? farClippingPlane = null
) {
// adds error if fieldOfView is out of bounds
if (fieldOfView != null) {
assertFovInBounds(fov: (float)fieldOfView);
}
// count is out of bounds
if (thirdPartyCameraId >= thirdPartyCameras.Count || thirdPartyCameraId < 0) {
throw new ArgumentOutOfRangeException(
$"thirdPartyCameraId: {thirdPartyCameraId} (int: default=0) must in 0 <= thirdPartyCameraId < len(thirdPartyCameras)={thirdPartyCameras.Count}."
);
}
Camera thirdPartyCamera = thirdPartyCameras[thirdPartyCameraId];
// keeps positions at default values, if unspecified.
Vector3 oldPosition = thirdPartyCamera.gameObject.transform.position;
Vector3 targetPosition = parseOptionalVector3(optionalVector3: position, defaultsOnNull: oldPosition);
// keeps rotations at default values, if unspecified.
Vector3 oldRotation = thirdPartyCamera.gameObject.transform.localEulerAngles;
Vector3 targetRotation = parseOptionalVector3(optionalVector3: rotation, defaultsOnNull: oldRotation);
updateCameraProperties(
camera: thirdPartyCamera,
position: targetPosition,
rotation: targetRotation,
fieldOfView: fieldOfView == null ? thirdPartyCamera.fieldOfView : (float)fieldOfView,
skyboxColor: skyboxColor,
orthographic: orthographic,
orthographicSize: orthographicSize,
nearClippingPlane: nearClippingPlane,
farClippingPlane: farClippingPlane
);
}
private void addAgent(ServerAction action) {
Vector3 clonePosition = new Vector3(action.x, action.y, action.z);
BaseAgentComponent componentClone = UnityEngine.Object.Instantiate(primaryAgent.baseAgentComponent);
var agent = createAgentType(primaryAgent.GetType(), componentClone);
agent.IsVisible = action.makeAgentsVisible;
agent.actionDuration = this.actionDuration;
// clone.m_Camera.targetDisplay = this.agents.Count;
componentClone.transform.position = clonePosition;
UpdateAgentColor(agent, agentColors[this.agents.Count]);
#if PLATFORM_CLOUD_RENDERING
agent.m_Camera.targetTexture = createRenderTexture(this.primaryAgent.m_Camera.targetTexture.width, this.primaryAgent.m_Camera.targetTexture.height);
#endif
agent.ProcessControlCommand(action.dynamicServerAction);
}
private Vector3 agentStartPosition(BaseFPSAgentController agent) {
Transform t = agent.transform;
Vector3[] castDirections = new Vector3[] { t.forward, t.forward * -1, t.right, t.right * -1 };
RaycastHit maxHit = new RaycastHit();
Vector3 maxDirection = Vector3.zero;
RaycastHit hit;
CharacterController charContr = agent.m_CharacterController;
Vector3 p1 = t.position + charContr.center + Vector3.up * -charContr.height * 0.5f;
Vector3 p2 = p1 + Vector3.up * charContr.height;
foreach (Vector3 d in castDirections) {
if (Physics.CapsuleCast(p1, p2, charContr.radius, d, out hit)) {
if (hit.distance > maxHit.distance) {
maxHit = hit;
maxDirection = d;
}
}
}
if (maxHit.distance > (charContr.radius * 5)) {
return t.position + (maxDirection * (charContr.radius * 4));
}
return Vector3.zero;
}
public void UpdateAgentColor(BaseFPSAgentController agent, Color color) {
foreach (MeshRenderer r in agent.gameObject.GetComponentsInChildren<MeshRenderer>() as MeshRenderer[]) {
foreach (Material m in r.materials) {
if (m.name.Contains("Agent_Color_Mat")) {
m.color = color;
}
}
}
}
public IEnumerator ResetCoroutine(ServerAction response) {
// Setting all the agents invisible here is silly but necessary
// as otherwise the FirstPersonCharacterCull.cs script will
// try to disable renderers that are invalid (but not null)
// as the scene they existed in has changed.
for (int i = 0; i < agents.Count; i++) {
Destroy(agents[i].baseAgentComponent);
}
yield return null;
if (string.IsNullOrEmpty(response.sceneName)) {
UnityEngine.SceneManagement.SceneManager.LoadScene(UnityEngine.SceneManagement.SceneManager.GetActiveScene().name);
} else {
UnityEngine.SceneManagement.SceneManager.LoadScene(response.sceneName);
}
}
public void resetMaterials() {
ColorChanger colorChangeComponent = physicsSceneManager.GetComponent<ColorChanger>();
colorChangeComponent.ResetMaterials();
doResetMaterials = false;
doResetColors = false;
}
public void resetColors() {
ColorChanger colorChangeComponent = physicsSceneManager.GetComponent<ColorChanger>();
colorChangeComponent.ResetColors();
doResetColors = false;
}
public void Reset(ServerAction response) {
if (doResetMaterials) {
resetMaterials();
} else if (doResetColors) {
resetColors();
}
StartCoroutine(ResetCoroutine(response));
}
public bool SwitchScene(string sceneName) {
if (!string.IsNullOrEmpty(sceneName)) {
UnityEngine.SceneManagement.SceneManager.LoadScene(sceneName);
return true;
}
return false;
}
// Decide whether agent has stopped actions
// And if we need to capture a new frame
private void Update() {
physicsSceneManager.isSceneAtRest = true;// assume the scene is at rest by default
}
private void captureScreenAsync(List<KeyValuePair<string, byte[]>> payload, string key, Camera camera) {
RenderTexture tt = camera.targetTexture;
RenderTexture.active = tt;
camera.Render();
AsyncGPUReadback.Request(tt, 0, (request) =>
{
if (!request.hasError) {
var data = request.GetData<byte>().ToArray();
payload.Add(new KeyValuePair<string, byte[]>(key, data));
}
else
{
Debug.Log("Request error: " + request.hasError);
}
});
}
private byte[] captureScreen() {
if (tex.height != UnityEngine.Screen.height ||
tex.width != UnityEngine.Screen.width) {
tex = new Texture2D(UnityEngine.Screen.width, UnityEngine.Screen.height, TextureFormat.RGB24, false);
readPixelsRect = new Rect(0, 0, UnityEngine.Screen.width, UnityEngine.Screen.height);
}
tex.ReadPixels(readPixelsRect, 0, 0);
tex.Apply();
return tex.GetRawTextureData();
}
private void addThirdPartyCameraImage(List<KeyValuePair<string, byte[]>> payload, Camera camera) {
#if PLATFORM_CLOUD_RENDERING
captureScreenAsync(payload, "image-thirdParty-camera", camera);
#else
RenderTexture.active = camera.activeTexture;
camera.Render();
payload.Add(new KeyValuePair<string, byte[]>("image-thirdParty-camera", captureScreen()));
#endif
}
private void addImage(List<KeyValuePair<string, byte[]>> payload, BaseFPSAgentController agent) {
if (this.renderImage) {
#if PLATFORM_CLOUD_RENDERING
captureScreenAsync(payload, "image", agent.m_Camera);
#else
// XXX may not need this since we call render in captureScreenAsync
if (this.agents.Count > 1 || this.thirdPartyCameras.Count > 0) {
RenderTexture.active = agent.m_Camera.activeTexture;
agent.m_Camera.Render();
}
payload.Add(new KeyValuePair<string, byte[]>("image", captureScreen()));
#endif
}
}
private void resetImageSynthesis(Camera camera) {
ImageSynthesis imageSynthesis = camera.gameObject.GetComponentInChildren<ImageSynthesis>();
if (imageSynthesis != null && imageSynthesis.enabled) {
imageSynthesis.OnCameraChange();
imageSynthesis.OnSceneChange();
}
}
private void resetAllImageSynthesis() {
foreach (var agent in this.agents) {
resetImageSynthesis(agent.m_Camera);
}
foreach (var camera in this.thirdPartyCameras) {
resetImageSynthesis(camera);
}
}
public IEnumerator WaitOnResolutionChange(int width, int height) {
while (Screen.width != width || Screen.height != height) {
yield return null;
}
this.resetAllImageSynthesis();
this.primaryAgent.actionFinished(true);
}
public void ChangeQuality(string quality) {
string[] names = QualitySettings.names;
for (int i = 0; i < names.Length; i++) {
if (names[i] == quality) {
QualitySettings.SetQualityLevel(i, true);
break;
}
}
this.primaryAgent.actionFinished(true);
}
public void ChangeResolution(int x, int y) {
Screen.SetResolution(width: x, height: y, false);
Debug.Log("current screen resolution pre change: " + Screen.width + " height" + Screen.height);
#if PLATFORM_CLOUD_RENDERING
foreach (var agent in this.agents) {
var rt = agent.m_Camera.targetTexture;
rt.Release();
Destroy(rt);
agent.m_Camera.targetTexture = createRenderTexture(x, y);
}
foreach (var camera in this.thirdPartyCameras) {
var rt = camera.targetTexture;
rt.Release();
Destroy(rt);
camera.targetTexture = createRenderTexture(x, y);
}
#endif
StartCoroutine(WaitOnResolutionChange(width: x, height: y));
}
private void addObjectImage(List<KeyValuePair<string, byte[]>> payload, BaseFPSAgentController agent, ref MetadataWrapper metadata) {
if (this.renderInstanceSegmentation || this.renderSemanticSegmentation) {
if (!agent.imageSynthesis.hasCapturePass("_id")) {
Debug.LogError("Object Image not available in imagesynthesis - returning empty image");
}
byte[] bytes = agent.imageSynthesis.Encode("_id");
payload.Add(new KeyValuePair<string, byte[]>("image_ids", bytes));
List<ColorId> colors = new List<ColorId>();
foreach (Color key in agent.imageSynthesis.colorIds.Keys) {
ColorId cid = new ColorId();
cid.color = new ushort[] {
(ushort)Math.Round (key.r * 255),
(ushort)Math.Round (key.g * 255),
(ushort)Math.Round (key.b * 255)
};
cid.name = agent.imageSynthesis.colorIds[key];
colors.Add(cid);
}
metadata.colors = colors.ToArray();
}
}
private void addImageSynthesisImage(List<KeyValuePair<string, byte[]>> payload, ImageSynthesis synth, bool flag, string captureName, string fieldName) {
if (flag) {
if (!synth.hasCapturePass(captureName)) {
Debug.LogError(captureName + " not available - sending empty image");
}
byte[] bytes = synth.Encode(captureName);
payload.Add(new KeyValuePair<string, byte[]>(fieldName, bytes));
}
}
// Used for benchmarking only the server-side
// no call is made to the Python side
private IEnumerator EmitFrameNoClient() {
frameCounter += 1;
bool shouldRender = this.renderImage;
if (shouldRender) {
// we should only read the screen buffer after rendering is complete
yield return new WaitForEndOfFrame();
// must wait an additional frame when in synchronous mode otherwise the frame lags
yield return new WaitForEndOfFrame();
}
// NOTE: sequenceId is required in DynamicServerAction.
string msg = "{\"action\": \"RotateRight\", \"timeScale\": 90.0, \"sequenceId\": 0}";
ProcessControlCommand(msg);
}
public void createPayload(MultiAgentMetadata multiMeta, ThirdPartyCameraMetadata[] cameraMetadata, List<KeyValuePair<string, byte[]>> renderPayload, bool shouldRender) {
multiMeta.agents = new MetadataWrapper[this.agents.Count];
multiMeta.activeAgentId = this.activeAgentId;
multiMeta.sequenceId = this.currentSequenceId;
RenderTexture currentTexture = null;
if (shouldRender) {
currentTexture = RenderTexture.active;
for (int i = 0; i < this.thirdPartyCameras.Count; i++) {
ThirdPartyCameraMetadata cMetadata = new ThirdPartyCameraMetadata();
Camera camera = thirdPartyCameras.ToArray()[i];
cMetadata.thirdPartyCameraId = i;
cMetadata.position = camera.gameObject.transform.position;
cMetadata.rotation = camera.gameObject.transform.eulerAngles;
cMetadata.fieldOfView = camera.fieldOfView;
cameraMetadata[i] = cMetadata;
ImageSynthesis imageSynthesis = camera.gameObject.GetComponentInChildren<ImageSynthesis>() as ImageSynthesis;
addThirdPartyCameraImage(renderPayload, camera);
addImageSynthesisImage(renderPayload, imageSynthesis, this.renderDepthImage, "_depth", "image_thirdParty_depth");
addImageSynthesisImage(renderPayload, imageSynthesis, this.renderNormalsImage, "_normals", "image_thirdParty_normals");
addImageSynthesisImage(renderPayload, imageSynthesis, this.renderInstanceSegmentation, "_id", "image_thirdParty_image_ids");
addImageSynthesisImage(renderPayload, imageSynthesis, this.renderSemanticSegmentation, "_class", "image_thirdParty_classes");
addImageSynthesisImage(renderPayload, imageSynthesis, this.renderSemanticSegmentation, "_flow", "image_thirdParty_flow");// XXX fix this in a bit
}
}
for (int i = 0; i < this.agents.Count; i++) {
BaseFPSAgentController agent = this.agents[i];
MetadataWrapper metadata = agent.generateMetadataWrapper();
// This value may never change, but the purpose is to provide a way
// to be backwards compatible in the future by knowing the output format
// so that it can be converted if necessary on the Python side
metadata.depthFormat = DepthFormat.Meters.ToString();
metadata.agentId = i;
// we don't need to render the agent's camera for the first agent
if (shouldRender) {
addImage(renderPayload, agent);
addImageSynthesisImage(renderPayload, agent.imageSynthesis, this.renderDepthImage, "_depth", "image_depth");
addImageSynthesisImage(renderPayload, agent.imageSynthesis, this.renderNormalsImage, "_normals", "image_normals");
addObjectImage(renderPayload, agent, ref metadata);
addImageSynthesisImage(renderPayload, agent.imageSynthesis, this.renderSemanticSegmentation, "_class", "image_classes");
addImageSynthesisImage(renderPayload, agent.imageSynthesis, this.renderFlowImage, "_flow", "image_flow");
metadata.thirdPartyCameras = cameraMetadata;
}
multiMeta.agents[i] = metadata;
}
if (shouldRender) {
RenderTexture.active = currentTexture;
}
}
private string serializeMetadataJson(MultiAgentMetadata multiMeta) {
var jsonResolver = new ShouldSerializeContractResolver();
return Newtonsoft.Json.JsonConvert.SerializeObject(
multiMeta,
Newtonsoft.Json.Formatting.None,
new Newtonsoft.Json.JsonSerializerSettings() {
ReferenceLoopHandling = Newtonsoft.Json.ReferenceLoopHandling.Ignore,
ContractResolver = jsonResolver
}
);
}
private bool canEmit() {
bool emit = true;
foreach (BaseFPSAgentController agent in this.agents) {
if (agent.agentState != AgentState.Emit) {
emit = false;
break;
}
}
return this.agentManagerState == AgentState.Emit && emit;
}
private RenderTexture createRenderTexture(int width, int height) {
RenderTexture rt = new RenderTexture(width: width, height: height,depth:0, GraphicsFormat.R8G8B8A8_UNorm);
rt.antiAliasing = 4;
if (rt.Create()) {
Debug.Log(" created render texture with width= " + width + " height=" + height);
return rt;
} else {
// throw exception ?
Debug.LogError("Could not create a renderTexture");
return null;
}
}
public IEnumerator EmitFrame() {
while (true) {
bool shouldRender = this.renderImage && serverSideScreenshot;
yield return new WaitForEndOfFrame();
frameCounter += 1;
if (this.agentManagerState == AgentState.ActionComplete) {
this.agentManagerState = AgentState.Emit;
}