27using namespace std::string_literals;
38 const auto vc = client.GetClientVersion();
39 const auto vs = client.GetServerVersion();
42 "Version mismatch detected: You are trying to connect to a simulator",
43 "that might be incompatible with this API");
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);
73 const std::string &host,
75 const size_t worker_threads,
76 const bool enable_garbage_collection)
78 _client(host, port, worker_threads),
80 _gc_policy(enable_garbage_collection ?
100 for (
auto i = 0u; i < number_of_attempts; ++i) {
101 using namespace std::literals::chrono_literals;
108 if (episode.GetId() !=
id) {
112 throw_exception(std::runtime_error(
"failed to connect to newly created map"));
116 std::string opendrive,
121 constexpr auto custom_opendrive_map =
"OpenDriveMap";
123 return LoadEpisode(custom_opendrive_map, reset_settings);
133 _episode = std::make_shared<Episode>(
_client, std::weak_ptr<Simulator>(shared_from_this()));
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];
168 map_base_path += map_info.
name[i];
169 fill_base_string =
true;
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";
214 auto result =
_episode->WaitForState(timeout);
215 if (!result.has_value()) {
244 return MakeShared<BlueprintLibrary>(std::move(defs));
258 "synchronous mode enabled with variable delta seconds. It is highly "
259 "recommended to set 'fixed_delta_seconds' when running on synchronous mode.");
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].");
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.");
278 using namespace std::literals::chrono_literals;
290 auto nav =
_episode->CreateNavigationIfMissing();
297 auto nav =
_episode->CreateNavigationIfMissing();
303 if (walker ==
nullptr) {
308 auto nav =
_episode->CreateNavigationIfMissing();
309 nav->RegisterWalker(walker->GetId(), controller.
GetId());
314 if (walker ==
nullptr) {
319 auto nav =
_episode->CreateNavigationIfMissing();
320 nav->UnregisterWalker(walker->GetId(), controller.
GetId());
325 auto nav =
_episode->CreateNavigationIfMissing();
326 return nav->GetRandomLocation();
331 auto nav =
_episode->CreateNavigationIfMissing();
332 nav->SetPedestriansCrossFactor(percentage);
337 auto nav =
_episode->CreateNavigationIfMissing();
338 nav->SetPedestriansSeed(seed);
351 const std::string& socket_name) {
353 if (parent !=
nullptr) {
370 result->GetDisplayId(),
373 "garbage collection");
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();
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();
453 const std::vector<std::string> &objects_name,
460 const std::vector<std::string> &objects_name,
#define DEBUG_ASSERT(predicate)
#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.
EpisodeProxy & GetEpisode()
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
std::string GetMapData() 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 ¶ms)
void FreezeAllTrafficLights(bool frozen)
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)
rpc::Actor GetSpectator()
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 ¶meter, const rpc::TextureColor &Texture)
rpc::MapInfo GetMapInfo()
rpc::EpisodeSettings GetEpisodeSettings()
time_duration GetTimeout() const
rpc::Actor SpawnActor(const rpc::ActorDescription &description, const geom::Transform &transform)
auto GetId() const noexcept
Holds the current episode, and the current episode state.
std::shared_ptr< const EpisodeState > GetState() const
WorldSnapshot WaitForTick(time_duration timeout)
std::shared_ptr< Episode > _episode
bool ShouldUpdateMap(rpc::MapInfo &map_info)
void DisableForROS(const Sensor &sensor)
void RequestFile(const std::string &name) const
std::string _open_drive_file
void EnableForROS(const Sensor &sensor)
void RegisterAIController(const WalkerAIController &controller)
SharedPtr< LightManager > _light_manager
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.
bool IsEnabledForROS(const Sensor &sensor)
SharedPtr< BlueprintLibrary > GetBlueprintLibrary()
void GetReadyCurrentEpisode()
Simulator(const std::string &host, uint16_t port, size_t worker_threads=0u, bool enable_garbage_collection=false)
const GarbageCollectionPolicy _gc_policy
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
SharedPtr< Map > _cached_map
void ApplyColorTextureToObjects(const std::vector< std::string > &objects_name, const rpc::MaterialParameter ¶meter, 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 ¶ms, 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)
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()
bool DestroyActor(Actor &actor)
void SetPedestriansSeed(unsigned int seed)
boost::optional< geom::Location > GetRandomLocationFromNavigation()
EpisodeProxy GetCurrentEpisode()
void Send(const Sensor &sensor, std::string message)
streaming::Token GetStreamToken() const
boost::optional< double > fixed_delta_seconds
double max_substep_delta_time
Positive time duration up to milliseconds resolution.
static time_duration milliseconds(size_t timeout)
constexpr auto to_chrono() const
static void ValidateVersions(Client &client)
EpisodeProxyImpl< EpisodeProxyPointerType::Weak > WeakEpisodeProxy
static bool SynchronizeFrame(uint64_t frame, const Episode &episode, time_duration timeout)
std::vector< std::pair< ActorId, VehicleLightState::flag_type > > VehicleLightStateList
This file contains definitions of common data structures used in traffic manager.
void throw_exception(const std::exception &e)
static void log_warning(Args &&... args)
boost::shared_ptr< T > SharedPtr
Use this SharedPtr (boost::shared_ptr) to keep compatibility with boost::python, but it would be nice...
static void log_debug(Args &&... args)
Seting for map generation from opendrive without additional geometry