public void Execute(JSONNode args) { var api = ApiManager.Instance; var uid = args["uid"].Value; if (api.Agents.TryGetValue(uid, out GameObject obj)) { api.StopLine.Add(obj); api.SendResult(); SIM.LogAPI(SIM.API.OnStopLineSet); } else { api.SendError($"Agent '{uid}' not found"); } }
public void Execute(JSONNode args) { var api = ApiManager.Instance; var uid = args["uid"].Value; if (api.Agents.TryGetValue(uid, out GameObject obj)) { api.Waypoints.Add(obj); api.SendResult(this); SIM.LogAPI(SIM.API.OnWaypointReached, obj.tag); } else { api.SendError(this, $"Agent '{uid}' not found"); } }
public void Execute(JSONNode args) { var api = ApiManager.Instance; var timeScale = args["time_scale"]; if (timeScale == null || timeScale.IsNull) { api.TimeScale = 1f; } else { api.TimeScale = timeScale.AsFloat; } SimulatorManager.SetTimeScale(api.TimeScale); var timeLimit = args["time_limit"].AsFloat; if (timeLimit != 0) { var frameLimit = (int)(timeLimit / Time.fixedDeltaTime); api.FrameLimit = api.CurrentFrame + frameLimit; } else { api.FrameLimit = 0; } //Start the scenario runner here var use_case_id = args["use_case_id"].AsInt; var scenario_id = args["scenario_id"].AsInt; var test_case_id = args["test_case_id"].AsInt; //ArrayList results; SimulatorManager.Instance.Scenario_Config(use_case_id, scenario_id, test_case_id); // var results_json = new JSONArray(); // foreach(String result in results) // { // results_json.Add(new JSONString(result)); // } // api.SendResult(results_json); SIM.LogAPI(SIM.API.SimulationRun, timeLimit.ToString()); }
public void Execute(JSONNode args) { var uid = args["uid"].Value; var waypoints = args["waypoints"].AsArray; var loop = args["loop"].AsBool; var api = ApiManager.Instance; if (waypoints.Count == 0) { api.SendError(this, $"Waypoint list is empty"); return; } if (api.Agents.TryGetValue(uid, out GameObject obj)) { var ped = obj.GetComponent <PedestrianController>(); if (ped == null) { api.SendError(this, $"Agent '{uid}' is not a pedestrian agent"); return; } var wp = new List <WalkWaypoint>(); for (int i = 0; i < waypoints.Count; i++) { wp.Add(new WalkWaypoint() { Position = waypoints[i]["position"].ReadVector3(), Speed = waypoints[i]["speed"].AsFloat, Idle = waypoints[i]["idle"].AsFloat, TriggerDistance = waypoints[i]["trigger_distance"].AsFloat, Trigger = DeserializeTrigger(waypoints[i]["trigger"]) }); } ped.FollowWaypoints(wp, loop); api.RegisterAgentWithWaypoints(ped.gameObject); api.SendResult(this); SIM.LogAPI(SIM.API.FollowWaypoints, "Pedestrian"); } else { api.SendError(this, $"Agent '{uid}' not found"); } }
public void Execute(JSONNode args) { var uid = args["uid"].Value; var waypoints = args["waypoints"].AsArray; var loop = args["loop"].AsBool; var api = ApiManager.Instance; if (waypoints.Count == 0) { api.SendError($"Waypoint list is empty"); return; } if (api.Agents.TryGetValue(uid, out GameObject obj)) { var npc = obj.GetComponent <NPCController>(); if (npc == null) { api.SendError($"Agent '{uid}' is not a NPC agent"); return; } var wp = new List <DriveWaypoint>(); for (int i = 0; i < waypoints.Count; i++) { wp.Add(new DriveWaypoint() { Position = waypoints[i]["position"].ReadVector3(), Speed = waypoints[i]["speed"].AsFloat, Angle = waypoints[i]["angle"].ReadVector3(), Idle = waypoints[i]["idle"].AsFloat, Deactivate = waypoints[i]["deactivate"].AsBool, TriggerDistance = waypoints[i]["trigger_distance"].AsFloat }); } npc.SetFollowWaypoints(wp, loop); api.SendResult(); SIM.LogAPI(SIM.API.FollowWaypoints, "NPC"); } else { api.SendError($"Agent '{uid}' not found"); } }
public static void Run() { var api = ApiManager.Instance; foreach (var kv in api.Agents) { var obj = kv.Value; var sensors = obj.GetComponentsInChildren <SensorBase>(); foreach (var sensor in sensors) { var suid = api.SensorUID[sensor]; api.Sensors.Remove(suid); api.SensorUID.Remove(sensor); } } api.Reset(); SIM.LogAPI(SIM.API.SimulationReset); }
public void Execute(JSONNode args) { var uid = args["uid"].Value; var api = ApiManager.Instance; if (api.Agents.TryGetValue(uid, out GameObject obj)) { var sensors = obj.GetComponentsInChildren <SensorBase>(); if (SimulatorManager.InstanceAvailable) { foreach (var sensor in sensors) { SimulatorManager.Instance.Sensors.UnregisterSensor(sensor); } } SimulatorManager.Instance.AgentManager.DestroyAgent(obj); var npc = obj.GetComponent <NPCController>(); if (npc != null) { SimulatorManager.Instance.NPCManager.DespawnVehicle(npc); } var ped = obj.GetComponent <PedestrianController>(); if (ped != null) { SimulatorManager.Instance.PedestrianManager.DespawnPedestrianApi(ped); } api.Agents.Remove(uid); api.AgentUID.Remove(obj); api.SendResult(this); SIM.LogAPI(SIM.API.RemoveAgent, obj.name); } else { api.SendError(this, $"Agent '{uid}' not found"); } }
public static void Run() { var api = ApiManager.Instance; foreach (var kv in api.Agents) { var obj = kv.Value; var sensors = obj.GetComponentsInChildren <SensorBase>(); foreach (var sensor in sensors) { var suid = api.SensorUID[sensor]; api.Sensors.Remove(suid); api.SensorUID.Remove(sensor); } var sim = SimulatorManager.Instance; if (obj.GetComponent <VehicleController>() != null) { sim.AgentManager.DestroyAgent(obj); } var npc = obj.GetComponent <NPCController>(); if (npc != null) { sim.NPCManager.DespawnVehicle(npc); } var ped = obj.GetComponent <PedestrianController>(); if (ped != null) { sim.PedestrianManager.DespawnPedestrianApi(ped); } } api.Reset(); SIM.LogAPI(SIM.API.SimulationReset); }
public void Execute(JSONNode args) { var api = ApiManager.Instance; var sim = SimulatorManager.Instance; var timeScale = args["time_scale"]; if (timeScale == null || timeScale.IsNull) { api.TimeScale = 1f; } else { api.TimeScale = timeScale.AsFloat; } SimulatorManager.SetTimeScale(api.TimeScale); var timeLimit = args["time_limit"].AsFloat; if (timeLimit != 0) { var frameLimit = (int)(timeLimit / Time.fixedDeltaTime); api.FrameLimit = api.CurrentFrame + frameLimit; } else { api.FrameLimit = 0; } SIM.LogAPI(SIM.API.SimulationRun, timeLimit.ToString()); if (sim.NPCManager.startTime == 0f) { sim.NPCManager.startTime = sim.CurrentTime; } //sim.AnalysisManager.AnalysisInit(); }
public void Execute(JSONNode args) { var uid = args["uid"].Value; var isLeft = args["isLeftChange"].AsBool; var api = ApiManager.Instance; if (api.Agents.TryGetValue(uid, out GameObject obj)) { var npc = obj.GetComponent <NPCController>(); if (npc == null) { api.SendError(this, $"Agent '{uid}' is not a NPC agent"); return; } npc.ForceLaneChange(isLeft); api.SendResult(this); SIM.LogAPI(SIM.API.OnLaneChangeSet); } else { api.SendError(this, $"Agent '{uid}' not found"); } }
public void Execute(JSONNode args) { var sim = Object.FindObjectOfType <SimulatorManager>(); var api = ApiManager.Instance; if (sim == null) { api.SendError("SimulatorManager not found! Is scene loaded?"); return; } var name = args["name"].Value; var type = args["type"].AsInt; var position = args["state"]["transform"]["position"].ReadVector3(); var rotation = args["state"]["transform"]["rotation"].ReadVector3(); var velocity = args["state"]["velocity"].ReadVector3(); var angular_velocity = args["state"]["angular_velocity"].ReadVector3(); if (type == (int)AgentType.Ego) { var agents = SimulatorManager.Instance.AgentManager; GameObject agentGO = null; using (var db = DatabaseManager.Open()) { var sql = Sql.Builder.From("vehicles").Where("name = @0", name); var vehicle = db.SingleOrDefault <VehicleModel>(sql); if (vehicle == null) { api.SendError($"Vehicle '{name}' is not available"); return; } else { var prefab = AquirePrefab(vehicle); if (prefab == null) { return; } var config = new AgentConfig() { Name = vehicle.Name, Prefab = prefab, Sensors = vehicle.Sensors, }; if (vehicle.BridgeType != null) { config.Bridge = Web.Config.Bridges.Find(bridge => bridge.Name == vehicle.BridgeType); if (config.Bridge == null) { api.SendError($"Bridge '{vehicle.BridgeType}' not available"); return; } } agentGO = agents.SpawnAgent(config); agentGO.transform.position = position; agentGO.transform.rotation = Quaternion.Euler(rotation); if (agents.ActiveAgents.Count == 1) { agents.SetCurrentActiveAgent(agentGO); } var rb = agentGO.GetComponent <Rigidbody>(); rb.velocity = velocity; rb.angularVelocity = angular_velocity; } } var uid = System.Guid.NewGuid().ToString(); Debug.Assert(agentGO != null); api.Agents.Add(uid, agentGO); api.AgentUID.Add(agentGO, uid); var sensors = agentGO.GetComponentsInChildren <SensorBase>(); foreach (var sensor in sensors) { var sensor_uid = System.Guid.NewGuid().ToString(); api.SensorUID.Add(sensor, sensor_uid); api.Sensors.Add(sensor_uid, sensor); } api.SendResult(new JSONString(uid)); SIM.LogAPI(SIM.API.AddAgentEgo, name); } else if (type == (int)AgentType.Npc) { var go = SimulatorManager.Instance.NPCManager.SpawnVehicle(name, position, Quaternion.Euler(rotation)); var npc = go.GetComponent <NPCController>(); npc.Control = NPCController.ControlType.Manual; var body = go.GetComponent <Rigidbody>(); body.velocity = velocity; body.angularVelocity = angular_velocity; var uid = go.name; api.Agents.Add(uid, go); api.AgentUID.Add(go, uid); api.SendResult(new JSONString(go.name)); SIM.LogAPI(SIM.API.AddAgentNPC, name); } else if (type == (int)AgentType.Pedestrian) { var pedManager = SimulatorManager.Instance.PedestrianManager; if (!pedManager.gameObject.activeSelf) { var sceneName = SceneManager.GetActiveScene().name; api.SendError($"{sceneName} is missing Pedestrian NavMesh"); return; } var ped = pedManager.SpawnPedestrianApi(name, position, Quaternion.Euler(rotation)); if (ped == null) { api.SendError($"Unknown '{name}' pedestrian name"); return; } var uid = System.Guid.NewGuid().ToString(); api.Agents.Add(uid, ped); api.AgentUID.Add(ped, uid); api.SendResult(new JSONString(uid)); SIM.LogAPI(SIM.API.AddAgentPedestrian, name); } else { api.SendError($"Unsupported '{args["type"]}' type"); } }
static IEnumerator LoadMapAssets(LoadScene sourceCommand, MapModel map, string name, int?seed = null) { var api = ApiManager.Instance; AssetBundle textureBundle = null; AssetBundle mapBundle = null; ZipFile zip = new ZipFile(map.LocalPath); try { Manifest manifest; ZipEntry entry = zip.GetEntry("manifest"); using (var ms = zip.GetInputStream(entry)) { int streamSize = (int)entry.Size; byte[] buffer = new byte[streamSize]; streamSize = ms.Read(buffer, 0, streamSize); manifest = new Deserializer().Deserialize <Manifest>(Encoding.UTF8.GetString(buffer)); } if (manifest.bundleFormat != BundleConfig.MapBundleFormatVersion) { api.SendError(sourceCommand, "Out of date Map AssetBundle. Please check content website for updated bundle or rebuild the bundle."); api.ActionsSemaphore.Unlock(); yield break; } if (zip.FindEntry($"{manifest.assetGuid}_environment_textures", true) != -1) { var texStream = zip.GetInputStream(zip.GetEntry($"{manifest.assetGuid}_environment_textures")); textureBundle = AssetBundle.LoadFromStream(texStream, 0, 1 << 20); } string platform = SystemInfo.operatingSystemFamily == OperatingSystemFamily.Windows ? "windows" : "linux"; var mapStream = zip.GetInputStream(zip.GetEntry($"{manifest.assetGuid}_environment_main_{platform}")); mapBundle = AssetBundle.LoadFromStream(mapStream, 0, 1 << 20); if (mapBundle == null) { api.SendError(sourceCommand, $"Failed to load environment from '{map.Name}' asset bundle"); api.ActionsSemaphore.Unlock(); yield break; } textureBundle?.LoadAllAssets(); var scenes = mapBundle.GetAllScenePaths(); if (scenes.Length != 1) { api.SendError(sourceCommand, $"Unsupported environment in '{map.Name}' asset bundle, only 1 scene expected"); api.ActionsSemaphore.Unlock(); yield break; } var sceneName = Path.GetFileNameWithoutExtension(scenes[0]); var clusters = Loader.Instance.SimConfig?.Clusters; var isMasterSimulation = clusters != null && clusters.Length != 0; var loadAdditive = isMasterSimulation && SceneManager.GetSceneByName(Loader.Instance.LoaderScene).isLoaded; var loader = SceneManager.LoadSceneAsync(sceneName, loadAdditive ? LoadSceneMode.Additive : LoadSceneMode.Single); yield return(new WaitUntil(() => loader.isDone)); if (loadAdditive) { SceneManager.SetActiveScene(SceneManager.GetSceneByName(sceneName)); } SIM.LogAPI(SIM.API.SimulationLoad, sceneName); if (Loader.Instance.SimConfig != null) { Loader.Instance.SimConfig.Seed = seed; Loader.Instance.SimConfig.MapName = name; Loader.Instance.SimConfig.MapUrl = map.Url; } var sim = Loader.CreateSimulatorManager(); sim.Init(seed); if (isMasterSimulation) { Loader.Instance.Network.Master.InitializeSimulation(sim.gameObject); } else if (Loader.Instance.Network.IsClient) { Loader.Instance.Network.Client.InitializeSimulation(sim.gameObject); } } finally { textureBundle?.Unload(false); mapBundle?.Unload(false); zip.Close(); } api.Reset(); api.CurrentScene = name; api.ActionsSemaphore.Unlock(); api.SendResult(sourceCommand); }
static IEnumerator DoLoad(string name, int?seed = null) { var api = ApiManager.Instance; using (var db = Database.DatabaseManager.Open()) { var sql = Sql.Builder.From("maps").Where("name = @0", name); var map = db.FirstOrDefault <Database.MapModel>(sql); if (map == null) { api.SendError($"Environment '{name}' is not available"); yield break; } AssetBundle textureBundle = null; AssetBundle mapBundle = null; ZipFile zip = new ZipFile(map.LocalPath); try { Manifest manifest; ZipEntry entry = zip.GetEntry("manifest"); using (var ms = zip.GetInputStream(entry)) { int streamSize = (int)entry.Size; byte[] buffer = new byte[streamSize]; streamSize = ms.Read(buffer, 0, streamSize); manifest = new Deserializer().Deserialize <Manifest>(Encoding.UTF8.GetString(buffer)); } if (manifest.bundleFormat != BundleConfig.MapBundleFormatVersion) { api.SendError("Out of date Map AssetBundle. Please check content website for updated bundle or rebuild the bundle."); yield break; } var texStream = zip.GetInputStream(zip.GetEntry($"{manifest.bundleGuid}_environment_textures")); textureBundle = AssetBundle.LoadFromStream(texStream, 0, 1 << 20); string platform = SystemInfo.operatingSystemFamily == OperatingSystemFamily.Windows ? "windows" : "linux"; var mapStream = zip.GetInputStream(zip.GetEntry($"{manifest.bundleGuid}_environment_main_{platform}")); mapBundle = AssetBundle.LoadFromStream(mapStream, 0, 1 << 20); if (mapBundle == null || textureBundle == null) { api.SendError($"Failed to load environment from '{map.Name}' asset bundle"); yield break; } textureBundle.LoadAllAssets(); var scenes = mapBundle.GetAllScenePaths(); if (scenes.Length != 1) { api.SendError($"Unsupported environment in '{map.Name}' asset bundle, only 1 scene expected"); yield break; } var sceneName = Path.GetFileNameWithoutExtension(scenes[0]); var loader = SceneManager.LoadSceneAsync(sceneName); yield return(new WaitUntil(() => loader.isDone)); SIM.LogAPI(SIM.API.SimulationLoad, sceneName); var sim = UnityEngine.Object.Instantiate(Loader.Instance.SimulatorManagerPrefab); sim.name = "SimulatorManager"; sim.Init(seed); } finally { textureBundle?.Unload(false); mapBundle?.Unload(false); zip.Close(); } // TODO deactivate environment props if needed api.Reset(); api.CurrentScene = name; api.SendResult(); } }
public void Execute(JSONNode args) { var sim = Object.FindObjectOfType <SimulatorManager>(); var api = ApiManager.Instance; if (sim == null) { api.SendError(this, "SimulatorManager not found! Is scene loaded?"); return; } var name = args["name"].Value; var type = args["type"].AsInt; var position = args["state"]["transform"]["position"].ReadVector3(); var rotation = args["state"]["transform"]["rotation"].ReadVector3(); var velocity = args["state"]["velocity"].ReadVector3(); var angular_velocity = args["state"]["angular_velocity"].ReadVector3(); string uid; var argsUid = args["uid"]; if (argsUid == null) { uid = System.Guid.NewGuid().ToString(); // Add uid key to arguments, as it will be distributed to the clients' simulations if (Loader.Instance.Network.IsMaster) { args.Add("uid", uid); } } else { uid = argsUid.Value; } if (type == (int)AgentType.Ego) { var agents = SimulatorManager.Instance.AgentManager; GameObject agentGO = null; using (var db = DatabaseManager.Open()) { var sql = Sql.Builder.From("vehicles").Where("name = @0", name); var vehicle = db.FirstOrDefault <VehicleModel>(sql); if (vehicle == null) { var url = args["url"]; //Disable using url on master simulation if (Loader.Instance.Network.IsMaster || string.IsNullOrEmpty(url)) { api.SendError(this, $"Vehicle '{name}' is not available"); return; } DownloadVehicleFromUrl(args, name, url); return; } else { var prefab = AquirePrefab(vehicle); if (prefab == null) { return; } var config = new AgentConfig() { Name = vehicle.Name, Prefab = prefab, Sensors = vehicle.Sensors, }; if (!string.IsNullOrEmpty(vehicle.BridgeType)) { config.Bridge = Web.Config.Bridges.Find(bridge => bridge.Name == vehicle.BridgeType); if (config.Bridge == null) { api.SendError(this, $"Bridge '{vehicle.BridgeType}' not available"); return; } } agentGO = agents.SpawnAgent(config); agentGO.transform.position = position; agentGO.transform.rotation = Quaternion.Euler(rotation); if (agents.ActiveAgents.Count == 1) { agents.SetCurrentActiveAgent(agentGO); } var rb = agentGO.GetComponent <Rigidbody>(); rb.velocity = velocity; rb.angularVelocity = angular_velocity; // Add url key to arguments, as it will be distributed to the clients' simulations if (Loader.Instance.Network.IsMaster) { args.Add("url", vehicle.Url); } } } Debug.Assert(agentGO != null); api.Agents.Add(uid, agentGO); api.AgentUID.Add(agentGO, uid); var sensors = agentGO.GetComponentsInChildren <SensorBase>(true); foreach (var sensor in sensors) { var sensorUid = System.Guid.NewGuid().ToString(); if (SimulatorManager.InstanceAvailable) { SimulatorManager.Instance.Sensors.AppendUid(sensor, sensorUid); } } api.SendResult(this, new JSONString(uid)); SIM.LogAPI(SIM.API.AddAgentEgo, name); } else if (type == (int)AgentType.Npc) { var colorData = args["color"].ReadVector3(); var color = new Color(); if (colorData != new Vector3(-1, -1, -1)) { color = new Color(colorData.x, colorData.y, colorData.z); } var go = SimulatorManager.Instance.NPCManager.SpawnVehicle(name, uid, position, Quaternion.Euler(rotation), color); var npc = go.GetComponent <NPCController>(); npc.Control = NPCController.ControlType.Manual; var body = go.GetComponent <Rigidbody>(); body.velocity = velocity; body.angularVelocity = angular_velocity; uid = go.name; api.Agents.Add(uid, go); api.AgentUID.Add(go, uid); api.SendResult(this, new JSONString(go.name)); SIM.LogAPI(SIM.API.AddAgentNPC, name); // Override the color argument as NPCController may change the NPC color if (Loader.Instance.Network.IsMaster) { var colorVector = new Vector3(npc.NPCColor.r, npc.NPCColor.g, npc.NPCColor.b); args["color"].WriteVector3(colorVector); } } else if (type == (int)AgentType.Pedestrian) { var pedManager = SimulatorManager.Instance.PedestrianManager; if (!pedManager.gameObject.activeSelf) { var sceneName = SceneManager.GetActiveScene().name; api.SendError(this, $"{sceneName} is missing Pedestrian NavMesh"); return; } var ped = pedManager.SpawnPedestrianApi(name, uid, position, Quaternion.Euler(rotation)); if (ped == null) { api.SendError(this, $"Unknown '{name}' pedestrian name"); return; } api.Agents.Add(uid, ped); api.AgentUID.Add(ped, uid); api.SendResult(this, new JSONString(uid)); SIM.LogAPI(SIM.API.AddAgentPedestrian, name); } else { api.SendError(this, $"Unsupported '{args["type"]}' type"); } }
public void Execute(JSONNode args) { var sim = Object.FindObjectOfType <SimulatorManager>(); var api = ApiManager.Instance; if (sim == null) { api.SendError("SimulatorManager not found! Is scene loaded?"); return; } var name = args["name"].Value; var type = args["type"].AsInt; var position = args["state"]["transform"]["position"].ReadVector3(); var rotation = args["state"]["transform"]["rotation"].ReadVector3(); var velocity = args["state"]["velocity"].ReadVector3(); var angular_velocity = args["state"]["angular_velocity"].ReadVector3(); if (type == (int)AgentType.Ego) { var agents = SimulatorManager.Instance.AgentManager; GameObject agentGO = null; using (var db = Database.DatabaseManager.Open()) { var sql = Sql.Builder.From("vehicles").Where("name = @0", name); var vehicle = db.SingleOrDefault <Database.VehicleModel>(sql); if (vehicle == null) { api.SendError($"Vehicle '{name}' is not available"); return; } var bundlePath = vehicle.LocalPath; AssetBundle textureBundle = null; AssetBundle vehicleBundle = null; using (ZipFile zip = new ZipFile(bundlePath)) { Manifest manifest; ZipEntry entry = zip.GetEntry("manifest"); using (var ms = zip.GetInputStream(entry)) { int streamSize = (int)entry.Size; byte[] buffer = new byte[streamSize]; streamSize = ms.Read(buffer, 0, streamSize); manifest = new Deserializer().Deserialize <Manifest>(Encoding.UTF8.GetString(buffer, 0, streamSize)); } var texStream = zip.GetInputStream(zip.GetEntry($"{manifest.bundleGuid}_vehicle_textures")); textureBundle = AssetBundle.LoadFromStream(texStream, 0, 1 << 20); string platform = SystemInfo.operatingSystemFamily == OperatingSystemFamily.Windows ? "windows" : "linux"; var mapStream = zip.GetInputStream(zip.GetEntry($"{manifest.bundleGuid}_vehicle_main_{platform}")); vehicleBundle = AssetBundle.LoadFromStream(mapStream, 0, 1 << 20); if (vehicleBundle == null) { api.SendError($"Failed to load vehicle from '{bundlePath}' asset bundle"); return; } try { var vehicleAssets = vehicleBundle.GetAllAssetNames(); if (vehicleAssets.Length != 1) { api.SendError($"Unsupported '{bundlePath}' vehicle asset bundle, only 1 asset expected"); return; } if (!AssetBundle.GetAllLoadedAssetBundles().Contains(textureBundle)) { textureBundle.LoadAllAssets(); } var prefab = vehicleBundle.LoadAsset <GameObject>(vehicleAssets[0]); var config = new AgentConfig() { Name = vehicle.Name, Prefab = prefab, Sensors = vehicle.Sensors, }; if (vehicle.BridgeType != null) { config.Bridge = Web.Config.Bridges.Find(bridge => bridge.Name == vehicle.BridgeType); if (config.Bridge == null) { api.SendError($"Bridge '{vehicle.BridgeType}' not available"); return; } } agentGO = agents.SpawnAgent(config); agentGO.transform.position = position; agentGO.transform.rotation = Quaternion.Euler(rotation); if (agents.ActiveAgents.Count == 1) { agents.SetCurrentActiveAgent(agentGO); } var rb = agentGO.GetComponent <Rigidbody>(); rb.velocity = velocity; rb.angularVelocity = angular_velocity; } finally { textureBundle.Unload(false); vehicleBundle.Unload(false); } } } var uid = System.Guid.NewGuid().ToString(); Debug.Assert(agentGO != null); api.Agents.Add(uid, agentGO); api.AgentUID.Add(agentGO, uid); var sensors = agentGO.GetComponentsInChildren <SensorBase>(); foreach (var sensor in sensors) { var sensor_uid = System.Guid.NewGuid().ToString(); api.SensorUID.Add(sensor, sensor_uid); api.Sensors.Add(sensor_uid, sensor); } api.SendResult(new JSONString(uid)); SIM.LogAPI(SIM.API.AddAgentEgo, name); } else if (type == (int)AgentType.Npc) { var go = SimulatorManager.Instance.NPCManager.SpawnVehicle(name, position, Quaternion.Euler(rotation)); var npc = go.GetComponent <NPCController>(); npc.Control = NPCController.ControlType.Manual; var body = go.GetComponent <Rigidbody>(); body.velocity = velocity; body.angularVelocity = angular_velocity; var uid = go.name; api.Agents.Add(uid, go); api.AgentUID.Add(go, uid); api.SendResult(new JSONString(go.name)); SIM.LogAPI(SIM.API.AddAgentNPC, name); } else if (type == (int)AgentType.Pedestrian) { var ped = SimulatorManager.Instance.PedestrianManager.SpawnPedestrianApi(name, position, Quaternion.Euler(rotation)); if (ped == null) { api.SendError($"Unknown '{name}' pedestrian name"); return; } var uid = System.Guid.NewGuid().ToString(); api.Agents.Add(uid, ped); api.AgentUID.Add(ped, uid); api.SendResult(new JSONString(uid)); SIM.LogAPI(SIM.API.AddAgentPedestrian, name); } else { api.SendError($"Unsupported '{args["type"]}' type"); } }