CARLA
 
载入中...
搜索中...
未找到
Simulator.cpp
浏览该文件的文档.
1// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
2// de Barcelona (UAB).
3//
4// This work is licensed under the terms of the MIT license.
5// For a copy, see <https://opensource.org/licenses/MIT>.
6
8
9#include "carla/Debug.h"
10#include "carla/Exception.h"
11#include "carla/Logging.h"
15#include "carla/client/Map.h"
16#include "carla/client/Sensor.h"
23
24#include <exception>
25#include <thread>
26
27using namespace std::string_literals;
28
29namespace carla {
30namespace client {
31namespace detail {
32
33 // ===========================================================================
34 // -- Static local methods ---------------------------------------------------
35 // ===========================================================================
36
37 static void ValidateVersions(Client &client) {
38 const auto vc = client.GetClientVersion();
39 const auto vs = client.GetServerVersion();
40 if (vc != vs) {
42 "Version mismatch detected: You are trying to connect to a simulator",
43 "that might be incompatible with this API");
44 log_warning("Client API version =", vc);
45 log_warning("Simulator API version =", vs);
46 }
47 }
48
49 static bool SynchronizeFrame(uint64_t frame, const Episode &episode, time_duration timeout) {
50 bool result = true;
51 auto start = std::chrono::system_clock::now();
52 while (frame > episode.GetState()->GetTimestamp().frame) {
53 std::this_thread::yield();
54 auto end = std::chrono::system_clock::now();
55 auto diff = std::chrono::duration_cast<std::chrono::milliseconds>(end-start);
56 if(timeout.to_chrono() < diff) {
57 result = false;
58 break;
59 }
60 }
61 if(result) {
63 }
64
65 return result;
66 }
67
68 // ===========================================================================
69 // -- Constructor ------------------------------------------------------------
70 // ===========================================================================
71
73 const std::string &host,
74 const uint16_t port,
75 const size_t worker_threads,
76 const bool enable_garbage_collection)
77 : LIBCARLA_INITIALIZE_LIFETIME_PROFILER("SimulatorClient("s + host + ":" + std::to_string(port) + ")"),
78 _client(host, port, worker_threads),
79 _light_manager(new LightManager()),
80 _gc_policy(enable_garbage_collection ?
82
83 // ===========================================================================
84 // -- Load a new episode -----------------------------------------------------
85 // ===========================================================================
86
87 EpisodeProxy Simulator::LoadEpisode(std::string map_name, bool reset_settings, rpc::MapLayer map_layers) {
88 const auto id = GetCurrentEpisode().GetId();
89 _client.LoadEpisode(std::move(map_name), reset_settings, map_layers);
90
91 // We are waiting 50ms for the server to reload the episode.
92 // If in this time we have not detected a change of episode, we try again
93 // 'number_of_attempts' times.
94 // TODO This time is completly arbitrary so we need to improve
95 // this pipeline to not depend in this time because this timeout
96 // could result that the client resume the simulation in different
97 // initial ticks when loading a map in syncronous mode.
98 size_t number_of_attempts = _client.GetTimeout().milliseconds() / 50u;
99
100 for (auto i = 0u; i < number_of_attempts; ++i) {
101 using namespace std::literals::chrono_literals;
104
105 _episode->WaitForState(50ms);
106 auto episode = GetCurrentEpisode();
107
108 if (episode.GetId() != id) {
109 return episode;
110 }
111 }
112 throw_exception(std::runtime_error("failed to connect to newly created map"));
113 }
114
116 std::string opendrive,
117 const rpc::OpendriveGenerationParameters & params, bool reset_settings) {
118 // The "OpenDriveMap" is an ".umap" located in:
119 // "carla/Unreal/CarlaUE4/Content/Carla/Maps/"
120 // It will load the last sended OpenDRIVE by client's "LoadOpenDriveEpisode()"
121 constexpr auto custom_opendrive_map = "OpenDriveMap";
122 _client.CopyOpenDriveToServer(std::move(opendrive), params);
123 return LoadEpisode(custom_opendrive_map, reset_settings);
124 }
125
126 // ===========================================================================
127 // -- Access to current episode ----------------------------------------------
128 // ===========================================================================
129
131 if (_episode == nullptr) {
133 _episode = std::make_shared<Episode>(_client, std::weak_ptr<Simulator>(shared_from_this()));
134 _episode->Listen();
135 if (!GetEpisodeSettings().synchronous_mode) {
137 }
138 _light_manager->SetEpisode(WeakEpisodeProxy{shared_from_this()});
139 }
140 }
143 return EpisodeProxy{shared_from_this()};
144 }
145
147 if (!_cached_map) {
148 return true;
149 }
150 if (map_info.name != _cached_map->GetName() ||
151 _open_drive_file.size() != _cached_map->GetOpenDrive().size()) {
152 return true;
153 }
154 return false;
155 }
156
158 DEBUG_ASSERT(_episode != nullptr);
159 if (!_cached_map || _episode->HasMapChangedSinceLastCall()) {
160 rpc::MapInfo map_info = _client.GetMapInfo();
161 std::string map_name;
162 std::string map_base_path;
163 bool fill_base_string = false;
164 for (int i = map_info.name.size() - 1; i >= 0; --i) {
165 if (fill_base_string == false && map_info.name[i] != '/') {
166 map_name += map_info.name[i];
167 } else {
168 map_base_path += map_info.name[i];
169 fill_base_string = true;
170 }
171 }
172 std::reverse(map_name.begin(), map_name.end());
173 std::reverse(map_base_path.begin(), map_base_path.end());
174 std::string XODRFolder = map_base_path + "/OpenDrive/" + map_name + ".xodr";
175 if (FileTransfer::FileExists(XODRFolder) == false) _client.GetRequiredFiles();
177 _cached_map = MakeShared<Map>(map_info, _open_drive_file);
178 }
179
180 return _cached_map;
181 }
182
183 // ===========================================================================
184 // -- Required files ---------------------------------------------------------
185 // ===========================================================================
186
187
188 bool Simulator::SetFilesBaseFolder(const std::string &path) {
189 return _client.SetFilesBaseFolder(path);
190 }
191
192 std::vector<std::string> Simulator::GetRequiredFiles(const std::string &folder, const bool download) const {
193 return _client.GetRequiredFiles(folder, download);
194 }
195
196 void Simulator::RequestFile(const std::string &name) const {
197 _client.RequestFile(name);
198 }
199
200 std::vector<uint8_t> Simulator::GetCacheFile(const std::string &name, const bool request_otherwise) const {
201 return _client.GetCacheFile(name, request_otherwise);
202 }
203
204 // ===========================================================================
205 // -- Tick -------------------------------------------------------------------
206 // ===========================================================================
207
209 DEBUG_ASSERT(_episode != nullptr);
210
211 // tick pedestrian navigation
213
214 auto result = _episode->WaitForState(timeout);
215 if (!result.has_value()) {
217 }
218 return *result;
219 }
220
221 uint64_t Simulator::Tick(time_duration timeout) {
222 DEBUG_ASSERT(_episode != nullptr);
223
224 // tick pedestrian navigation
226
227 // send tick command
228 const auto frame = _client.SendTickCue();
229
230 // waits until new episode is received
231 bool result = SynchronizeFrame(frame, *_episode, timeout);
232 if (!result) {
234 }
235 return frame;
236 }
237
238 // ===========================================================================
239 // -- Access to global objects in the episode --------------------------------
240 // ===========================================================================
241
243 auto defs = _client.GetActorDefinitions();
244 return MakeShared<BlueprintLibrary>(std::move(defs));
245 }
246
250
254
256 if (settings.synchronous_mode && !settings.fixed_delta_seconds) {
258 "synchronous mode enabled with variable delta seconds. It is highly "
259 "recommended to set 'fixed_delta_seconds' when running on synchronous mode.");
260 }
261 else if (settings.synchronous_mode && settings.substepping) {
262 if(settings.max_substeps < 1 || settings.max_substeps > 16) {
264 "synchronous mode and substepping are enabled but the number of substeps is not valid. "
265 "Please be aware that this value needs to be in the range [1-16].");
266 }
267 double n_substeps = settings.fixed_delta_seconds.get() / settings.max_substep_delta_time;
268
269 if (n_substeps > static_cast<double>(settings.max_substeps)) {
271 "synchronous mode and substepping are enabled but the values for the simulation are not valid. "
272 "The values should fulfil fixed_delta_seconds <= max_substep_delta_time * max_substeps. "
273 "Be very careful about that, the time deltas are not guaranteed.");
274 }
275 }
276 const auto frame = _client.SetEpisodeSettings(settings);
277
278 using namespace std::literals::chrono_literals;
279 SynchronizeFrame(frame, *_episode, 1s);
280
281 return frame;
282 }
283
284 // ===========================================================================
285 // -- AI ---------------------------------------------------------------------
286 // ===========================================================================
287
288 std::shared_ptr<WalkerNavigation> Simulator::GetNavigation() {
289 DEBUG_ASSERT(_episode != nullptr);
290 auto nav = _episode->CreateNavigationIfMissing();
291 return nav;
292 }
293
294 // tick pedestrian navigation
296 DEBUG_ASSERT(_episode != nullptr);
297 auto nav = _episode->CreateNavigationIfMissing();
298 nav->Tick(_episode);
299 }
300
302 auto walker = controller.GetParent();
303 if (walker == nullptr) {
304 throw_exception(std::runtime_error(controller.GetDisplayId() + ": not attached to walker"));
305 return;
306 }
307 DEBUG_ASSERT(_episode != nullptr);
308 auto nav = _episode->CreateNavigationIfMissing();
309 nav->RegisterWalker(walker->GetId(), controller.GetId());
310 }
311
313 auto walker = controller.GetParent();
314 if (walker == nullptr) {
315 throw_exception(std::runtime_error(controller.GetDisplayId() + ": not attached to walker"));
316 return;
317 }
318 DEBUG_ASSERT(_episode != nullptr);
319 auto nav = _episode->CreateNavigationIfMissing();
320 nav->UnregisterWalker(walker->GetId(), controller.GetId());
321 }
322
323 boost::optional<geom::Location> Simulator::GetRandomLocationFromNavigation() {
324 DEBUG_ASSERT(_episode != nullptr);
325 auto nav = _episode->CreateNavigationIfMissing();
326 return nav->GetRandomLocation();
327 }
328
330 DEBUG_ASSERT(_episode != nullptr);
331 auto nav = _episode->CreateNavigationIfMissing();
332 nav->SetPedestriansCrossFactor(percentage);
333 }
334
335 void Simulator::SetPedestriansSeed(unsigned int seed) {
336 DEBUG_ASSERT(_episode != nullptr);
337 auto nav = _episode->CreateNavigationIfMissing();
338 nav->SetPedestriansSeed(seed);
339 }
340
341 // ===========================================================================
342 // -- General operations with actors -----------------------------------------
343 // ===========================================================================
344
346 const ActorBlueprint &blueprint,
347 const geom::Transform &transform,
348 Actor *parent,
349 rpc::AttachmentType attachment_type,
351 const std::string& socket_name) {
352 rpc::Actor actor;
353 if (parent != nullptr) {
355 blueprint.MakeActorDescription(),
356 transform,
357 parent->GetId(),
358 attachment_type,
359 socket_name);
360 } else {
361 actor = _client.SpawnActor(
362 blueprint.MakeActorDescription(),
363 transform);
364 }
365 DEBUG_ASSERT(_episode != nullptr);
366 _episode->RegisterActor(actor);
367 const auto gca = (gc == GarbageCollectionPolicy::Inherit ? _gc_policy : gc);
368 auto result = ActorFactory::MakeActor(GetCurrentEpisode(), actor, gca);
369 log_debug(
370 result->GetDisplayId(),
371 "created",
372 gca == GarbageCollectionPolicy::Enabled ? "with" : "without",
373 "garbage collection");
374 return result;
375 }
376
378 bool success = true;
379 success = _client.DestroyActor(actor.GetId());
380 if (success) {
381 // Remove it's persistent state so it cannot access the client anymore.
382 actor.GetEpisode().Clear();
383 log_debug(actor.GetDisplayId(), "destroyed.");
384 } else {
385 log_debug("failed to destroy", actor.GetDisplayId());
386 }
387 return success;
388 }
389
390 // ===========================================================================
391 // -- Operations with sensors ------------------------------------------------
392 // ===========================================================================
393
395 const Sensor &sensor,
396 std::function<void(SharedPtr<sensor::SensorData>)> callback) {
397 DEBUG_ASSERT(_episode != nullptr);
400 [cb=std::move(callback), ep=WeakEpisodeProxy{shared_from_this()}](auto buffer) {
401 auto data = sensor::Deserializer::Deserialize(std::move(buffer));
402 data->_episode = ep.TryLock();
403 cb(std::move(data));
404 });
405 }
406
409 // If in the future we need to unsubscribe from each gbuffer individually, it should be done here.
410 }
411
415
419
423
425 Actor &actor,
426 uint32_t gbuffer_id,
427 std::function<void(SharedPtr<sensor::SensorData>)> callback) {
428 _client.SubscribeToGBuffer(actor.GetId(), gbuffer_id,
429 [cb=std::move(callback), ep=WeakEpisodeProxy{shared_from_this()}](auto buffer) {
430 auto data = sensor::Deserializer::Deserialize(std::move(buffer));
431 data->_episode = ep.TryLock();
432 cb(std::move(data));
433 });
434 }
435
436 void Simulator::UnSubscribeFromGBuffer(Actor &actor, uint32_t gbuffer_id) {
437 _client.UnSubscribeFromGBuffer(actor.GetId(), gbuffer_id);
438 }
439
443
444 void Simulator::Send(const Sensor &sensor, std::string message) {
445 _client.Send(sensor.GetId(), message);
446 }
447
448 // =========================================================================
449 /// -- Texture updating operations
450 // =========================================================================
451
453 const std::vector<std::string> &objects_name,
454 const rpc::MaterialParameter& parameter,
455 const rpc::TextureColor& Texture) {
456 _client.ApplyColorTextureToObjects(objects_name, parameter, Texture);
457 }
458
460 const std::vector<std::string> &objects_name,
461 const rpc::MaterialParameter& parameter,
462 const rpc::TextureFloatColor& Texture) {
463 _client.ApplyColorTextureToObjects(objects_name, parameter, Texture);
464 }
465
466 std::vector<std::string> Simulator::GetNamesOfAllObjects() const {
468 }
469
470} // namespace detail
471} // namespace client
472} // namespace carla
#define DEBUG_ASSERT(predicate)
Definition Debug.h:66
#define LIBCARLA_INITIALIZE_LIFETIME_PROFILER(display_name)
Contains all the necessary information for spawning an Actor.
rpc::ActorDescription MakeActorDescription() const
Represents an actor in the simulation.
static bool FileExists(std::string file)
static SharedPtr< Actor > MakeActor(EpisodeProxy episode, rpc::Actor actor_description, GarbageCollectionPolicy garbage_collection_policy)
Create an Actor based on the provided actor_description.
SharedPtr< Actor > GetParent() const
const rpc::Actor & GetActorDescription() const
const std::string & GetDisplayId() const
Provides communication with the rpc and streaming servers of a CARLA simulator.
const std::string GetEndpoint() const
bool IsEnabledForROS(const streaming::Token &token)
void DisableForROS(const streaming::Token &token)
bool SetFilesBaseFolder(const std::string &path)
void RequestFile(const std::string &name) const
void Send(rpc::ActorId ActorId, std::string message)
void UnSubscribeFromGBuffer(rpc::ActorId ActorId, uint32_t GBufferId)
void UnSubscribeFromStream(const streaming::Token &token)
rpc::VehicleLightStateList GetVehiclesLightStates()
Returns a list of pairs where the firts element is the vehicle ID and the second one is the light sta...
std::vector< std::string > GetRequiredFiles(const std::string &folder="", const bool download=true) const
void LoadEpisode(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layer=rpc::MapLayer::All)
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)
rpc::Actor SpawnActorWithParent(const rpc::ActorDescription &description, const geom::Transform &transform, rpc::ActorId parent, rpc::AttachmentType attachment_type, const std::string &socket_name="")
void SubscribeToStream(const streaming::Token &token, std::function< void(Buffer)> callback)
std::vector< std::string > GetNamesOfAllObjects() const
void CopyOpenDriveToServer(std::string opendrive, const rpc::OpendriveGenerationParameters &params)
bool DestroyActor(rpc::ActorId actor)
std::vector< uint8_t > GetCacheFile(const std::string &name, const bool request_otherwise=true) const
void EnableForROS(const streaming::Token &token)
std::vector< rpc::ActorDefinition > GetActorDefinitions()
void SubscribeToGBuffer(rpc::ActorId ActorId, uint32_t GBufferId, std::function< void(Buffer)> callback)
void ApplyColorTextureToObjects(const std::vector< std::string > &objects_name, const rpc::MaterialParameter &parameter, const rpc::TextureColor &Texture)
rpc::EpisodeSettings GetEpisodeSettings()
rpc::Actor SpawnActor(const rpc::ActorDescription &description, const geom::Transform &transform)
Holds the current episode, and the current episode state.
Definition Episode.h:36
std::shared_ptr< const EpisodeState > GetState() const
Definition Episode.h:49
WorldSnapshot WaitForTick(time_duration timeout)
std::shared_ptr< Episode > _episode
Definition Simulator.h:834
bool ShouldUpdateMap(rpc::MapInfo &map_info)
void DisableForROS(const Sensor &sensor)
void RequestFile(const std::string &name) const
void EnableForROS(const Sensor &sensor)
void RegisterAIController(const WalkerAIController &controller)
SharedPtr< LightManager > _light_manager
Definition Simulator.h:832
SharedPtr< Actor > SpawnActor(const ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent=nullptr, rpc::AttachmentType attachment_type=rpc::AttachmentType::Rigid, GarbageCollectionPolicy gc=GarbageCollectionPolicy::Inherit, const std::string &socket_name="")
Spawns an actor into the simulation.
std::vector< std::string > GetRequiredFiles(const std::string &folder="", const bool download=true) const
SharedPtr< Actor > MakeActor(rpc::Actor actor_description, GarbageCollectionPolicy gc=GarbageCollectionPolicy::Disabled)
Creates an actor instance out of a description of an existing actor.
Definition Simulator.h:350
bool IsEnabledForROS(const Sensor &sensor)
SharedPtr< BlueprintLibrary > GetBlueprintLibrary()
Simulator(const std::string &host, uint16_t port, size_t worker_threads=0u, bool enable_garbage_collection=false)
Definition Simulator.cpp:72
const GarbageCollectionPolicy _gc_policy
Definition Simulator.h:836
rpc::VehicleLightStateList GetVehiclesLightStates()
Returns a list of pairs where the firts element is the vehicle ID and the second one is the light sta...
void UnSubscribeFromGBuffer(Actor &sensor, uint32_t gbuffer_id)
void SubscribeToSensor(const Sensor &sensor, std::function< void(SharedPtr< sensor::SensorData >)> callback)
void UnregisterAIController(const WalkerAIController &controller)
std::vector< uint8_t > GetCacheFile(const std::string &name, const bool request_otherwise) const
void ApplyColorTextureToObjects(const std::vector< std::string > &objects_name, const rpc::MaterialParameter &parameter, const rpc::TextureColor &Texture)
– Texture updating operations
std::shared_ptr< WalkerNavigation > GetNavigation()
bool SetFilesBaseFolder(const std::string &path)
SharedPtr< Actor > GetSpectator()
EpisodeProxy LoadOpenDriveEpisode(std::string opendrive, const rpc::OpendriveGenerationParameters &params, bool reset_settings=true)
void SetPedestriansCrossFactor(float percentage)
void FreezeAllTrafficLights(bool frozen)
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)
void UnSubscribeFromSensor(Actor &sensor)
EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layers=rpc::MapLayer::All)
Definition Simulator.cpp:87
uint64_t Tick(time_duration timeout)
void SubscribeToGBuffer(Actor &sensor, uint32_t gbuffer_id, std::function< void(SharedPtr< sensor::SensorData >)> callback)
std::vector< std::string > GetNamesOfAllObjects() const
SharedPtr< Map > GetCurrentMap()
rpc::EpisodeSettings GetEpisodeSettings()
Definition Simulator.h:248
bool DestroyActor(Actor &actor)
void SetPedestriansSeed(unsigned int seed)
boost::optional< geom::Location > GetRandomLocationFromNavigation()
void Send(const Sensor &sensor, std::string message)
streaming::Token GetStreamToken() const
Definition rpc/Actor.h:45
std::string name
Definition MapInfo.h:21
Positive time duration up to milliseconds resolution.
Definition Time.h:19
static time_duration milliseconds(size_t timeout)
Definition Time.h:26
constexpr auto to_chrono() const
Definition Time.h:50
static void ValidateVersions(Client &client)
Definition Simulator.cpp:37
EpisodeProxyImpl< EpisodeProxyPointerType::Weak > WeakEpisodeProxy
static bool SynchronizeFrame(uint64_t frame, const Episode &episode, time_duration timeout)
Definition Simulator.cpp:49
std::vector< std::pair< ActorId, VehicleLightState::flag_type > > VehicleLightStateList
This file contains definitions of common data structures used in traffic manager.
Definition Carla.cpp:133
void throw_exception(const std::exception &e)
Definition Carla.cpp:135
static void log_warning(Args &&... args)
Definition Logging.h:96
boost::shared_ptr< T > SharedPtr
Use this SharedPtr (boost::shared_ptr) to keep compatibility with boost::python, but it would be nice...
Definition Memory.h:20
static void log_debug(Args &&... args)
Definition Logging.h:68
Seting for map generation from opendrive without additional geometry