CARLA
Simulator.cpp
Go to the documentation of this file.
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 
27 using namespace std::string_literals;
28 
29 namespace carla {
30 namespace client {
31 namespace 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 
72  Simulator::Simulator(
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) {
136  WaitForTick(_client.GetTimeout());
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
212  NavigationTick();
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
225  NavigationTick();
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 
249  }
250 
252  return MakeActor(_client.GetSpectator());
253  }
254 
256  if (settings.synchronous_mode && !settings.fixed_delta_seconds) {
257  log_warning(
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) {
263  log_warning(
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)) {
270  log_warning(
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 
329  void Simulator::SetPedestriansCrossFactor(float percentage) {
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  rpc::Actor actor;
352  if (parent != nullptr) {
354  blueprint.MakeActorDescription(),
355  transform,
356  parent->GetId(),
357  attachment_type);
358  } else {
359  actor = _client.SpawnActor(
360  blueprint.MakeActorDescription(),
361  transform);
362  }
363  DEBUG_ASSERT(_episode != nullptr);
364  _episode->RegisterActor(actor);
365  const auto gca = (gc == GarbageCollectionPolicy::Inherit ? _gc_policy : gc);
366  auto result = ActorFactory::MakeActor(GetCurrentEpisode(), actor, gca);
367  log_debug(
368  result->GetDisplayId(),
369  "created",
370  gca == GarbageCollectionPolicy::Enabled ? "with" : "without",
371  "garbage collection");
372  return result;
373  }
374 
376  bool success = true;
377  success = _client.DestroyActor(actor.GetId());
378  if (success) {
379  // Remove it's persistent state so it cannot access the client anymore.
380  actor.GetEpisode().Clear();
381  log_debug(actor.GetDisplayId(), "destroyed.");
382  } else {
383  log_debug("failed to destroy", actor.GetDisplayId());
384  }
385  return success;
386  }
387 
388  // ===========================================================================
389  // -- Operations with sensors ------------------------------------------------
390  // ===========================================================================
391 
393  const Sensor &sensor,
394  std::function<void(SharedPtr<sensor::SensorData>)> callback) {
395  DEBUG_ASSERT(_episode != nullptr);
398  [cb=std::move(callback), ep=WeakEpisodeProxy{shared_from_this()}](auto buffer) {
399  auto data = sensor::Deserializer::Deserialize(std::move(buffer));
400  data->_episode = ep.TryLock();
401  cb(std::move(data));
402  });
403  }
404 
407  // If in the future we need to unsubscribe from each gbuffer individually, it should be done here.
408  }
409 
410  void Simulator::EnableForROS(const Sensor &sensor) {
412  }
413 
414  void Simulator::DisableForROS(const Sensor &sensor) {
416  }
417 
418  bool Simulator::IsEnabledForROS(const Sensor &sensor) {
420  }
421 
423  Actor &actor,
424  uint32_t gbuffer_id,
425  std::function<void(SharedPtr<sensor::SensorData>)> callback) {
426  _client.SubscribeToGBuffer(actor.GetId(), gbuffer_id,
427  [cb=std::move(callback), ep=WeakEpisodeProxy{shared_from_this()}](auto buffer) {
428  auto data = sensor::Deserializer::Deserialize(std::move(buffer));
429  data->_episode = ep.TryLock();
430  cb(std::move(data));
431  });
432  }
433 
434  void Simulator::UnSubscribeFromGBuffer(Actor &actor, uint32_t gbuffer_id) {
435  _client.UnSubscribeFromGBuffer(actor.GetId(), gbuffer_id);
436  }
437 
440  }
441 
442  // =========================================================================
443  /// -- Texture updating operations
444  // =========================================================================
445 
447  const std::vector<std::string> &objects_name,
448  const rpc::MaterialParameter& parameter,
449  const rpc::TextureColor& Texture) {
450  _client.ApplyColorTextureToObjects(objects_name, parameter, Texture);
451  }
452 
454  const std::vector<std::string> &objects_name,
455  const rpc::MaterialParameter& parameter,
456  const rpc::TextureFloatColor& Texture) {
457  _client.ApplyColorTextureToObjects(objects_name, parameter, Texture);
458  }
459 
460  std::vector<std::string> Simulator::GetNamesOfAllObjects() const {
461  return _client.GetNamesOfAllObjects();
462  }
463 
464 } // namespace detail
465 } // namespace client
466 } // namespace carla
rpc::VehicleLightStateList GetVehiclesLightStates()
Returns a list of pairs where the firts element is the vehicle ID and the second one is the light sta...
Definition: Simulator.cpp:247
std::shared_ptr< Episode > _episode
Definition: Simulator.h:779
bool DestroyActor(Actor &actor)
Definition: Simulator.cpp:375
streaming::Token GetStreamToken() const
Definition: rpc/Actor.h:45
Seting for map generation from opendrive without additional geometry.
static SharedPtr< SensorData > Deserialize(Buffer &&buffer)
static time_duration milliseconds(size_t timeout)
Definition: Time.h:26
bool SetFilesBaseFolder(const std::string &path)
Holds the current episode, and the current episode state.
Definition: Episode.h:34
void SubscribeToGBuffer(rpc::ActorId ActorId, uint32_t GBufferId, std::function< void(Buffer)> callback)
bool SetFilesBaseFolder(const std::string &path)
Definition: Simulator.cpp:188
static void ValidateVersions(Client &client)
Definition: Simulator.cpp:37
std::vector< rpc::ActorDefinition > GetActorDefinitions()
bool IsEnabledForROS(const streaming::Token &token)
std::shared_ptr< WalkerNavigation > GetNavigation()
Definition: Simulator.cpp:288
void throw_exception(const std::exception &e)
Definition: Carla.cpp:135
void reverse(I begin, I end)
Definition: pugixml.cpp:7358
bool IsEnabledForROS(const Sensor &sensor)
Definition: Simulator.cpp:418
std::vector< std::string > GetNamesOfAllObjects() const
void CopyOpenDriveToServer(std::string opendrive, const rpc::OpendriveGenerationParameters &params)
std::vector< std::string > GetNamesOfAllObjects() const
Definition: Simulator.cpp:460
std::vector< uint8_t > GetCacheFile(const std::string &name, const bool request_otherwise) const
Definition: Simulator.cpp:200
std::vector< uint8_t > GetCacheFile(const std::string &name, const bool request_otherwise=true) const
static SharedPtr< Actor > MakeActor(EpisodeProxy episode, rpc::Actor actor_description, GarbageCollectionPolicy garbage_collection_policy)
Create an Actor based on the provided actor_description.
std::vector< std::string > GetRequiredFiles(const std::string &folder="", const bool download=true) const
Definition: Simulator.cpp:192
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
SharedPtr< LightManager > _light_manager
Definition: Simulator.h:777
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
const GarbageCollectionPolicy _gc_policy
Definition: Simulator.h:781
rpc::EpisodeSettings GetEpisodeSettings()
SharedPtr< Actor > GetSpectator()
Definition: Simulator.cpp:251
std::vector< std::string > GetRequiredFiles(const std::string &folder="", const bool download=true) const
boost::optional< geom::Location > GetRandomLocationFromNavigation()
Definition: Simulator.cpp:323
void RequestFile(const std::string &name) const
void SubscribeToStream(const streaming::Token &token, std::function< void(Buffer)> callback)
rpc::VehicleLightStateList GetVehiclesLightStates()
Returns a list of pairs where the firts element is the vehicle ID and the second one is the light sta...
static void log_debug(Args &&...)
Definition: Logging.h:75
void EnableForROS(const Sensor &sensor)
Definition: Simulator.cpp:410
const std::string & GetDisplayId() const
SharedPtr< Map > _cached_map
Definition: Simulator.h:783
void DisableForROS(const streaming::Token &token)
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)
Definition: Simulator.cpp:255
#define DEBUG_ASSERT(predicate)
Definition: Debug.h:66
#define LIBCARLA_INITIALIZE_LIFETIME_PROFILER(display_name)
rpc::EpisodeSettings GetEpisodeSettings()
Definition: Simulator.h:248
void ApplyColorTextureToObjects(const std::vector< std::string > &objects_name, const rpc::MaterialParameter &parameter, const rpc::TextureColor &Texture)
void EnableForROS(const streaming::Token &token)
SharedPtr< Actor > SpawnActor(const ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent=nullptr, rpc::AttachmentType attachment_type=rpc::AttachmentType::Rigid, GarbageCollectionPolicy gc=GarbageCollectionPolicy::Inherit)
Spawns an actor into the simulation.
Definition: Simulator.cpp:345
static bool SynchronizeFrame(uint64_t frame, const Episode &episode, time_duration timeout)
Definition: Simulator.cpp:49
void FreezeAllTrafficLights(bool frozen)
Definition: Simulator.cpp:438
void LoadEpisode(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layer=rpc::MapLayer::All)
EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layers=rpc::MapLayer::All)
Definition: Simulator.cpp:87
void ApplyColorTextureToObjects(const std::vector< std::string > &objects_name, const rpc::MaterialParameter &parameter, const rpc::TextureColor &Texture)
– Texture updating operations
Definition: Simulator.cpp:446
void SubscribeToSensor(const Sensor &sensor, std::function< void(SharedPtr< sensor::SensorData >)> callback)
Definition: Simulator.cpp:392
void UnSubscribeFromSensor(Actor &sensor)
Definition: Simulator.cpp:405
static void log_warning(Args &&... args)
Definition: Logging.h:96
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:342
std::shared_ptr< const EpisodeState > GetState() const
Definition: Episode.h:49
Provides communication with the rpc and streaming servers of a CARLA simulator.
rpc::Actor SpawnActorWithParent(const rpc::ActorDescription &description, const geom::Transform &transform, rpc::ActorId parent, rpc::AttachmentType attachment_type)
void UnregisterAIController(const WalkerAIController &controller)
Definition: Simulator.cpp:312
void DisableForROS(const Sensor &sensor)
Definition: Simulator.cpp:414
SharedPtr< Actor > GetParent() const
Definition: ActorState.cpp:31
uint64_t Tick(time_duration timeout)
Definition: Simulator.cpp:221
rpc::Actor SpawnActor(const rpc::ActorDescription &description, const geom::Transform &transform)
SharedPtr< Map > GetCurrentMap()
Definition: Simulator.cpp:157
bool DestroyActor(rpc::ActorId actor)
EpisodeProxy LoadOpenDriveEpisode(std::string opendrive, const rpc::OpendriveGenerationParameters &params, bool reset_settings=true)
Definition: Simulator.cpp:115
rpc::ActorDescription MakeActorDescription() const
Represents an actor in the simulation.
Definition: client/Actor.h:18
void RequestFile(const std::string &name) const
Definition: Simulator.cpp:196
Positive time duration up to milliseconds resolution.
Definition: Time.h:19
std::string name
Definition: MapInfo.h:21
void UnSubscribeFromStream(const streaming::Token &token)
Contains all the necessary information for spawning an Actor.
void RegisterAIController(const WalkerAIController &controller)
Definition: Simulator.cpp:301
void SetPedestriansCrossFactor(float percentage)
Definition: Simulator.cpp:329
void UnSubscribeFromGBuffer(rpc::ActorId ActorId, uint32_t GBufferId)
void SubscribeToGBuffer(Actor &sensor, uint32_t gbuffer_id, std::function< void(SharedPtr< sensor::SensorData >)> callback)
Definition: Simulator.cpp:422
SharedPtr< BlueprintLibrary > GetBlueprintLibrary()
Definition: Simulator.cpp:242
constexpr auto to_chrono() const
Definition: Time.h:50
EpisodeProxyImpl< EpisodeProxyPointerType::Weak > WeakEpisodeProxy
Definition: EpisodeProxy.h:71
void UnSubscribeFromGBuffer(Actor &sensor, uint32_t gbuffer_id)
Definition: Simulator.cpp:434
bool ShouldUpdateMap(rpc::MapInfo &map_info)
Definition: Simulator.cpp:146
const std::string GetEndpoint() const
static bool FileExists(std::string file)
void SetPedestriansSeed(unsigned int seed)
Definition: Simulator.cpp:335
WorldSnapshot WaitForTick(time_duration timeout)
Definition: Simulator.cpp:208
const rpc::Actor & GetActorDescription() const
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)