CARLA
Simulator.h
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 
7 #pragma once
8 
9 #include "carla/Debug.h"
10 #include "carla/Memory.h"
11 #include "carla/NonCopyable.h"
12 #include "carla/client/Actor.h"
15 #include "carla/client/Vehicle.h"
16 #include "carla/client/Walker.h"
27 
28 #include <boost/optional.hpp>
29 
30 #include <memory>
31 
32 namespace carla {
33 namespace client {
34 
35  class ActorBlueprint;
36  class BlueprintLibrary;
37  class Map;
38  class Sensor;
39  class WalkerAIController;
40 
41 namespace detail {
42 
43  /// Connects and controls a CARLA Simulator.
44  class Simulator
45  : public std::enable_shared_from_this<Simulator>,
47  private NonCopyable {
48  public:
49 
50  // =========================================================================
51  /// @name Constructor
52  // =========================================================================
53  /// @{
54 
55  explicit Simulator(
56  const std::string &host,
57  uint16_t port,
58  size_t worker_threads = 0u,
59  bool enable_garbage_collection = false);
60 
61  /// @}
62  // =========================================================================
63  /// @name Load a new episode
64  // =========================================================================
65  /// @{
66 
67  EpisodeProxy ReloadEpisode(bool reset_settings = true) {
68  return LoadEpisode("", reset_settings);
69  }
70 
71  EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings = true, rpc::MapLayer map_layers = rpc::MapLayer::All);
72 
73  void LoadLevelLayer(rpc::MapLayer map_layers) const {
74  _client.LoadLevelLayer(map_layers);
75  }
76 
77  void UnloadLevelLayer(rpc::MapLayer map_layers) const {
78  _client.UnloadLevelLayer(map_layers);
79  }
80 
82  std::string opendrive,
84  bool reset_settings = true);
85 
86  /// @}
87  // =========================================================================
88  /// @name Access to current episode
89  // =========================================================================
90  /// @{
91 
92  /// @pre Cannot be called previous to GetCurrentEpisode.
93  auto GetCurrentEpisodeId() const {
94  DEBUG_ASSERT(_episode != nullptr);
95  return _episode->GetId();
96  }
97 
99 
100  /// @}
101  // =========================================================================
102  /// @name World snapshot
103  // =========================================================================
104  /// @{
105 
107  DEBUG_ASSERT(_episode != nullptr);
108  return WorldSnapshot{_episode->GetState()};
109  }
110 
111  /// @}
112  // =========================================================================
113  /// @name Map related methods
114  // =========================================================================
115  /// @{
116 
118 
119  std::vector<std::string> GetAvailableMaps() {
120  return _client.GetAvailableMaps();
121  }
122 
123  /// @}
124  // =========================================================================
125  /// @name Garbage collection policy
126  // =========================================================================
127  /// @{
128 
130  return _gc_policy;
131  }
132 
133  /// @}
134  // =========================================================================
135  /// @name Pure networking operations
136  // =========================================================================
137  /// @{
138 
140  _client.SetTimeout(timeout);
141  }
142 
144  return _client.GetTimeout();
145  }
146 
147  std::string GetClientVersion() {
148  return _client.GetClientVersion();
149  }
150 
151  std::string GetServerVersion() {
152  return _client.GetServerVersion();
153  }
154 
155  /// @}
156  // =========================================================================
157  /// @name Tick
158  // =========================================================================
159  /// @{
160 
162 
163  size_t RegisterOnTickEvent(std::function<void(WorldSnapshot)> callback) {
164  DEBUG_ASSERT(_episode != nullptr);
165  return _episode->RegisterOnTickEvent(std::move(callback));
166  }
167 
168  void RemoveOnTickEvent(size_t id) {
169  DEBUG_ASSERT(_episode != nullptr);
170  _episode->RemoveOnTickEvent(id);
171  }
172 
173  uint64_t Tick(time_duration timeout);
174 
175  /// @}
176  // =========================================================================
177  /// @name Access to global objects in the episode
178  // =========================================================================
179  /// @{
180 
181  std :: string GetEndpoint() {
182  return _client.GetEndpoint();
183  }
184 
185  /// Query to know if a Traffic Manager is running on port
186  bool IsTrafficManagerRunning(uint16_t port) const {
187  return _client.IsTrafficManagerRunning(port);
188  }
189 
190  /// Gets a pair filled with the <IP, port> of the Trafic Manager running on port.
191  /// If there is no Traffic Manager running the pair will be ("", 0)
192  std::pair<std::string, uint16_t> GetTrafficManagerRunning(uint16_t port) const {
193  return _client.GetTrafficManagerRunning(port);
194  }
195 
196  /// Informs that a Traffic Manager is running on <IP, port>
197  bool AddTrafficManagerRunning(std::pair<std::string, uint16_t> trafficManagerInfo) const {
198  return _client.AddTrafficManagerRunning(trafficManagerInfo);
199  }
200 
201  void DestroyTrafficManager(uint16_t port) const {
203  }
204 
205  void AddPendingException(std::string e) {
206  _episode->AddPendingException(e);
207  }
208 
210 
211  /// Returns a list of pairs where the firts element is the vehicle ID
212  /// and the second one is the light state
214 
216 
218  return _client.GetEpisodeSettings();
219  }
220 
221  uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings);
222 
224  return _client.GetWeatherParameters();
225  }
226 
228  _client.SetWeatherParameters(weather);
229  }
230 
232  return _client.GetVehiclePhysicsControl(vehicle.GetId());
233  }
234 
236  return _client.GetVehicleLightState(vehicle.GetId());
237  }
238 
239  /// Returns all the BBs of all the elements of the level
240  std::vector<geom::BoundingBox> GetLevelBBs(uint8_t queried_tag) const {
241  return _client.GetLevelBBs(queried_tag);
242  }
243 
244  std::vector<rpc::EnvironmentObject> GetEnvironmentObjects(uint8_t queried_tag) const {
245  return _client.GetEnvironmentObjects(queried_tag);
246  }
247 
249  std::vector<uint64_t> env_objects_ids,
250  bool enable) const {
251  _client.EnableEnvironmentObjects(env_objects_ids, enable);
252  }
253 
254  std::pair<bool,rpc::LabelledPoint> ProjectPoint(
255  geom::Location location, geom::Vector3D direction, float search_distance) const {
256  return _client.ProjectPoint(location, direction, search_distance);
257  }
258 
259  std::vector<rpc::LabelledPoint> CastRay(
260  geom::Location start_location, geom::Location end_location) const {
261  return _client.CastRay(start_location, end_location);
262  }
263 
264  /// @}
265  // =========================================================================
266  /// @name AI
267  // =========================================================================
268  /// @{
269 
270  void RegisterAIController(const WalkerAIController &controller);
271 
272  void UnregisterAIController(const WalkerAIController &controller);
273 
274  boost::optional<geom::Location> GetRandomLocationFromNavigation();
275 
276  std::shared_ptr<WalkerNavigation> GetNavigation() {
277  return _episode->GetNavigation();
278  }
279 
280  void SetPedestriansCrossFactor(float percentage);
281 
282  /// @}
283  // =========================================================================
284  /// @name General operations with actors
285  // =========================================================================
286  /// @{
287 
288  boost::optional<rpc::Actor> GetActorById(ActorId id) const {
289  DEBUG_ASSERT(_episode != nullptr);
290  return _episode->GetActorById(id);
291  }
292 
293  std::vector<rpc::Actor> GetActorsById(const std::vector<ActorId> &actor_ids) const {
294  DEBUG_ASSERT(_episode != nullptr);
295  return _episode->GetActorsById(actor_ids);
296  }
297 
298  std::vector<rpc::Actor> GetAllTheActorsInTheEpisode() const {
299  DEBUG_ASSERT(_episode != nullptr);
300  return _episode->GetActors();
301  }
302 
303  /// Creates an actor instance out of a description of an existing actor.
304  /// Note that this does not spawn an actor.
305  ///
306  /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
307  /// returned is provided with a custom deleter that calls Destroy() on the
308  /// actor. This method does not support GarbageCollectionPolicy::Inherit.
310  rpc::Actor actor_description,
313  return ActorFactory::MakeActor(GetCurrentEpisode(), std::move(actor_description), gc);
314  }
315 
316  /// Spawns an actor into the simulation.
317  ///
318  /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
319  /// returned is provided with a custom deleter that calls Destroy() on the
320  /// actor. If @gc is GarbageCollectionPolicy::Inherit, the default garbage
321  /// collection policy is used.
323  const ActorBlueprint &blueprint,
324  const geom::Transform &transform,
325  Actor *parent = nullptr,
328 
329  bool DestroyActor(Actor &actor);
330 
332  DEBUG_ASSERT(_episode != nullptr);
333  return _episode->GetState()->GetActorSnapshot(actor_id);
334  }
335 
336  ActorSnapshot GetActorSnapshot(const Actor &actor) const {
337  return GetActorSnapshot(actor.GetId());
338  }
339 
340  geom::Location GetActorLocation(const Actor &actor) const {
341  return GetActorSnapshot(actor).transform.location;
342  }
343 
345  return GetActorSnapshot(actor).transform;
346  }
347 
348  geom::Vector3D GetActorVelocity(const Actor &actor) const {
349  return GetActorSnapshot(actor).velocity;
350  }
351 
352  void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector) {
353  _client.SetActorTargetVelocity(actor.GetId(), vector);
354  }
355 
357  return GetActorSnapshot(actor).angular_velocity;
358  }
359 
360  void SetActorTargetAngularVelocity(const Actor &actor, const geom::Vector3D &vector) {
362  }
363  void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector) {
364  _client.EnableActorConstantVelocity(actor.GetId(), vector);
365  }
366 
367  void DisableActorConstantVelocity(const Actor &actor) {
369  }
370 
371  void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse) {
372  _client.AddActorImpulse(actor.GetId(), impulse);
373  }
374 
375  void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location) {
376  _client.AddActorImpulse(actor.GetId(), impulse, location);
377  }
378 
379  void AddActorForce(const Actor &actor, const geom::Vector3D &force) {
380  _client.AddActorForce(actor.GetId(), force);
381  }
382 
383  void AddActorForce(const Actor &actor, const geom::Vector3D &force, const geom::Vector3D &location) {
384  _client.AddActorForce(actor.GetId(), force, location);
385  }
386 
387  void AddActorAngularImpulse(const Actor &actor, const geom::Vector3D &vector) {
388  _client.AddActorAngularImpulse(actor.GetId(), vector);
389  }
390 
391  void AddActorTorque(const Actor &actor, const geom::Vector3D &torque) {
392  _client.AddActorAngularImpulse(actor.GetId(), torque);
393  }
394 
396  return GetActorSnapshot(actor).acceleration;
397  }
398 
399  void SetActorLocation(Actor &actor, const geom::Location &location) {
400  _client.SetActorLocation(actor.GetId(), location);
401  }
402 
403  void SetActorTransform(Actor &actor, const geom::Transform &transform) {
404  _client.SetActorTransform(actor.GetId(), transform);
405  }
406 
407  void SetActorSimulatePhysics(Actor &actor, bool enabled) {
408  _client.SetActorSimulatePhysics(actor.GetId(), enabled);
409  }
410 
411  void SetActorEnableGravity(Actor &actor, bool enabled) {
412  _client.SetActorEnableGravity(actor.GetId(), enabled);
413  }
414 
415  /// @}
416  // =========================================================================
417  /// @name Operations with vehicles
418  // =========================================================================
419  /// @{
420 
421  void SetVehicleAutopilot(Vehicle &vehicle, bool enabled = true) {
422  _client.SetActorAutopilot(vehicle.GetId(), enabled);
423  }
424 
425  void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
426  _client.ApplyControlToVehicle(vehicle.GetId(), control);
427  }
428 
429  void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
430  _client.ApplyControlToVehicle(vehicle.GetId(), control);
431  }
432 
433  void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control) {
434  _client.ApplyControlToWalker(walker.GetId(), control);
435  }
436 
438  _client.ApplyBoneControlToWalker(walker.GetId(), control);
439  }
440 
441  void ApplyPhysicsControlToVehicle(Vehicle &vehicle, const rpc::VehiclePhysicsControl &physicsControl) {
442  _client.ApplyPhysicsControlToVehicle(vehicle.GetId(), physicsControl);
443  }
444 
445  void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state) {
446  _client.SetLightStateToVehicle(vehicle.GetId(), light_state);
447  }
448 
449  void EnableCarSim(Vehicle &vehicle, std::string simfile_path) {
450  _client.EnableCarSim(vehicle.GetId(), simfile_path);
451  }
452 
453  void UseCarSimRoad(Vehicle &vehicle, bool enabled) {
454  _client.UseCarSimRoad(vehicle.GetId(), enabled);
455  }
456 
457  /// @}
458  // =========================================================================
459  /// @name Operations with the recorder
460  // =========================================================================
461  /// @{
462 
463  std::string StartRecorder(std::string name, bool additional_data) {
464  return _client.StartRecorder(std::move(name), additional_data);
465  }
466 
467  void StopRecorder(void) {
469  }
470 
471  std::string ShowRecorderFileInfo(std::string name, bool show_all) {
472  return _client.ShowRecorderFileInfo(std::move(name), show_all);
473  }
474 
475  std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
476  return _client.ShowRecorderCollisions(std::move(name), type1, type2);
477  }
478 
479  std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
480  return _client.ShowRecorderActorsBlocked(std::move(name), min_time, min_distance);
481  }
482 
483  std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id) {
484  return _client.ReplayFile(std::move(name), start, duration, follow_id);
485  }
486 
487  void SetReplayerTimeFactor(double time_factor) {
488  _client.SetReplayerTimeFactor(time_factor);
489  }
490 
491  void SetReplayerIgnoreHero(bool ignore_hero) {
492  _client.SetReplayerIgnoreHero(ignore_hero);
493  }
494 
495  void StopReplayer(bool keep_actors) {
496  _client.StopReplayer(keep_actors);
497  }
498 
499  /// @}
500  // =========================================================================
501  /// @name Operations with sensors
502  // =========================================================================
503  /// @{
504 
505  void SubscribeToSensor(
506  const Sensor &sensor,
507  std::function<void(SharedPtr<sensor::SensorData>)> callback);
508 
509  void UnSubscribeFromSensor(const Sensor &sensor);
510 
511  /// @}
512  // =========================================================================
513  /// @name Operations with traffic lights
514  // =========================================================================
515  /// @{
516 
517  void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState) {
518  _client.SetTrafficLightState(trafficLight.GetId(), trafficLightState);
519  }
520 
521  void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime) {
522  _client.SetTrafficLightGreenTime(trafficLight.GetId(), greenTime);
523  }
524 
525  void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime) {
526  _client.SetTrafficLightYellowTime(trafficLight.GetId(), yellowTime);
527  }
528 
529  void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime) {
530  _client.SetTrafficLightRedTime(trafficLight.GetId(), redTime);
531  }
532 
533  void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze) {
534  _client.FreezeTrafficLight(trafficLight.GetId(), freeze);
535  }
536 
537  void ResetTrafficLightGroup(TrafficLight &trafficLight) {
538  _client.ResetTrafficLightGroup(trafficLight.GetId());
539  }
540 
543  }
544 
545  std::vector<ActorId> GetGroupTrafficLights(TrafficLight &trafficLight) {
546  return _client.GetGroupTrafficLights(trafficLight.GetId());
547  }
548 
549  /// @}
550  // =========================================================================
551  /// @name Debug
552  // =========================================================================
553  /// @{
554 
555  void DrawDebugShape(const rpc::DebugShape &shape) {
556  _client.DrawDebugShape(shape);
557  }
558 
559  /// @}
560  // =========================================================================
561  /// @name Apply commands in batch
562  // =========================================================================
563  /// @{
564 
565  void ApplyBatch(std::vector<rpc::Command> commands, bool do_tick_cue) {
566  _client.ApplyBatch(std::move(commands), do_tick_cue);
567  }
568 
569  auto ApplyBatchSync(std::vector<rpc::Command> commands, bool do_tick_cue) {
570  return _client.ApplyBatchSync(std::move(commands), do_tick_cue);
571  }
572 
573  /// @}
574  // =========================================================================
575  /// @name Operations lights
576  // =========================================================================
577  /// @{
578 
580  return _light_manager;
581  }
582 
583  std::vector<rpc::LightState> QueryLightsStateToServer() const {
585  }
586 
588  std::vector<rpc::LightState>& lights,
589  bool discard_client = false) const {
590  _client.UpdateServerLightsState(lights, discard_client);
591  }
592 
593  size_t RegisterLightUpdateChangeEvent(std::function<void(WorldSnapshot)> callback) {
594  DEBUG_ASSERT(_episode != nullptr);
595  return _episode->RegisterLightUpdateChangeEvent(std::move(callback));
596  }
597 
599  DEBUG_ASSERT(_episode != nullptr);
600  _episode->RemoveLightUpdateChangeEvent(id);
601  }
602 
603  void FreezeAllTrafficLights(bool frozen);
604 
605  /// @}
606 
607  private:
608 
610 
612 
613  std::shared_ptr<Episode> _episode;
614 
616  };
617 
618 } // namespace detail
619 } // namespace client
620 } // namespace carla
void DisableActorConstantVelocity(const Actor &actor)
Definition: Simulator.h:367
void SetVehicleAutopilot(Vehicle &vehicle, bool enabled=true)
Definition: Simulator.h:421
void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition: Simulator.h:363
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:177
std::shared_ptr< Episode > _episode
Definition: Simulator.h:613
bool DestroyActor(Actor &actor)
Definition: Simulator.cpp:290
time_duration GetNetworkingTimeout()
Definition: Simulator.h:143
void AddPendingException(std::string e)
Definition: Simulator.h:205
boost::optional< rpc::Actor > GetActorById(ActorId id) const
Definition: Simulator.h:288
Seting for map generation from opendrive without additional geometry.
void SetLightStateToVehicle(rpc::ActorId vehicle, const rpc::VehicleLightState &light_state)
void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse)
Definition: Simulator.h:371
std::vector< rpc::LabelledPoint > CastRay(geom::Location start_location, geom::Location end_location) const
Definition: Simulator.h:259
std::vector< rpc::Actor > GetActorsById(const std::vector< ActorId > &actor_ids) const
Definition: Simulator.h:293
void SetActorTargetVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
void ApplyBoneControlToWalker(Walker &walker, const rpc::WalkerBoneControl &control)
Definition: Simulator.h:437
void SetActorLocation(rpc::ActorId actor, const geom::Location &location)
bool AddTrafficManagerRunning(std::pair< std::string, uint16_t > trafficManagerInfo) const
Informs the server that a Traffic Manager is running on <IP, port>
void ApplyPhysicsControlToVehicle(rpc::ActorId vehicle, const rpc::VehiclePhysicsControl &physics_control)
std::string ShowRecorderFileInfo(std::string name, bool show_all)
void EnableCarSim(rpc::ActorId vehicle, std::string simfile_path)
bool AddTrafficManagerRunning(std::pair< std::string, uint16_t > trafficManagerInfo) const
Informs that a Traffic Manager is running on <IP, port>
Definition: Simulator.h:197
ActorSnapshot GetActorSnapshot(ActorId actor_id) const
Definition: Simulator.h:331
std::vector< rpc::LightState > QueryLightsStateToServer() const
Definition: Simulator.h:583
void SetActorSimulatePhysics(Actor &actor, bool enabled)
Definition: Simulator.h:407
std::vector< std::string > GetAvailableMaps()
Definition: Simulator.h:119
void SetTrafficLightState(rpc::ActorId traffic_light, const rpc::TrafficLightState trafficLightState)
void UpdateServerLightsState(std::vector< rpc::LightState > &lights, bool discard_client=false) const
Definition: Simulator.h:587
void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState)
Definition: Simulator.h:517
rpc::VehiclePhysicsControl GetVehiclePhysicsControl(const Vehicle &vehicle) const
Definition: Simulator.h:231
void SetActorTransform(rpc::ActorId actor, const geom::Transform &transform)
SharedPtr< LightManager > GetLightManager() const
Definition: Simulator.h:579
void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition: Simulator.h:429
std::vector< ActorId > GetGroupTrafficLights(rpc::ActorId traffic_light)
void SetTrafficLightYellowTime(rpc::ActorId traffic_light, float yellow_time)
void EnableActorConstantVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime)
Definition: Simulator.h:521
static SharedPtr< Actor > MakeActor(EpisodeProxy episode, rpc::Actor actor_description, GarbageCollectionPolicy garbage_collection_policy)
Create an Actor based on the provided actor_description.
void SetWeatherParameters(const rpc::WeatherParameters &weather)
Definition: Simulator.h:227
void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition: Simulator.h:425
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:611
void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze)
Definition: Simulator.h:533
std::vector< std::pair< ActorId, VehicleLightState::flag_type > > VehicleLightStateList
This file contains definitions of common data structures used in traffic manager. ...
Definition: Carla.cpp:99
const GarbageCollectionPolicy _gc_policy
Definition: Simulator.h:615
size_t RegisterOnTickEvent(std::function< void(WorldSnapshot)> callback)
Definition: Simulator.h:163
rpc::EpisodeSettings GetEpisodeSettings()
SharedPtr< Actor > GetSpectator()
Definition: Simulator.cpp:181
void DrawDebugShape(const rpc::DebugShape &shape)
boost::optional< geom::Location > GetRandomLocationFromNavigation()
Definition: Simulator.cpp:242
Simulator(const std::string &host, uint16_t port, size_t worker_threads=0u, bool enable_garbage_collection=false)
Definition: Simulator.cpp:70
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
std::vector< ActorId > GetGroupTrafficLights(TrafficLight &trafficLight)
Definition: Simulator.h:545
void AddActorAngularImpulse(rpc::ActorId actor, const geom::Vector3D &vector)
void FreezeTrafficLight(rpc::ActorId traffic_light, bool freeze)
void SetReplayerIgnoreHero(bool ignore_hero)
void ResetTrafficLightGroup(rpc::ActorId traffic_light)
void SetActorTargetAngularVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition: Simulator.h:360
std::vector< rpc::EnvironmentObject > GetEnvironmentObjects(uint8_t queried_tag) const
Definition: Simulator.h:244
bool IsTrafficManagerRunning(uint16_t port) const
Querry to know if a Traffic Manager is running on port.
void AddActorAngularImpulse(const Actor &actor, const geom::Vector3D &vector)
Definition: Simulator.h:387
void RemoveOnTickEvent(size_t id)
Definition: Simulator.h:168
void ApplyControlToVehicle(rpc::ActorId vehicle, const rpc::VehicleControl &control)
void UnSubscribeFromSensor(const Sensor &sensor)
Definition: Simulator.cpp:320
void LoadLevelLayer(rpc::MapLayer map_layer) const
void ApplyBatch(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition: Simulator.h:565
void UseCarSimRoad(Vehicle &vehicle, bool enabled)
Definition: Simulator.h:453
void StopReplayer(bool keep_actors)
Definition: Simulator.h:495
void SetActorLocation(Actor &actor, const geom::Location &location)
Definition: Simulator.h:399
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
Definition: Simulator.h:479
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)
Definition: Simulator.cpp:185
void DrawDebugShape(const rpc::DebugShape &shape)
Definition: Simulator.h:555
#define DEBUG_ASSERT(predicate)
Definition: Debug.h:66
rpc::EpisodeSettings GetEpisodeSettings()
Definition: Simulator.h:217
std::vector< rpc::LabelledPoint > CastRay(geom::Location start_location, geom::Location end_location) const
void RemoveLightUpdateChangeEvent(size_t id)
Definition: Simulator.h:598
void SetReplayerTimeFactor(double time_factor)
std::pair< bool, rpc::LabelledPoint > ProjectPoint(geom::Location location, geom::Vector3D direction, float search_distance) const
Definition: Simulator.h:254
void SetActorAutopilot(rpc::ActorId vehicle, bool enabled)
rpc::VehiclePhysicsControl GetVehiclePhysicsControl(rpc::ActorId vehicle) const
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:260
std::string StartRecorder(std::string name, bool additional_data)
void ApplyBoneControlToWalker(rpc::ActorId walker, const rpc::WalkerBoneControl &control)
Connects and controls a CARLA Simulator.
Definition: Simulator.h:44
rpc::WeatherParameters GetWeatherParameters()
void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime)
Definition: Simulator.h:529
void EnableCarSim(Vehicle &vehicle, std::string simfile_path)
Definition: Simulator.h:449
void FreezeAllTrafficLights(bool frozen)
Definition: Simulator.cpp:324
void EnableEnvironmentObjects(std::vector< uint64_t > env_objects_ids, bool enable) const
Definition: Simulator.h:248
std::pair< std::string, uint16_t > GetTrafficManagerRunning(uint16_t port) const
Gets a pair filled with the <IP, port> of the Trafic Manager running on port.
void AddActorForce(const Actor &actor, const geom::Vector3D &force)
Definition: Simulator.h:379
EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layers=rpc::MapLayer::All)
Definition: Simulator.cpp:85
#define RELEASE_ASSERT(pred)
Definition: Debug.h:84
void ApplyBatch(std::vector< rpc::Command > commands, bool do_tick_cue)
std::vector< geom::BoundingBox > GetLevelBBs(uint8_t queried_tag) const
Returns all the BBs of all the elements of the level.
void DestroyTrafficManager(uint16_t port) const
carla::ActorId ActorId
EpisodeProxy ReloadEpisode(bool reset_settings=true)
Definition: Simulator.h:67
std::string ShowRecorderFileInfo(std::string name, bool show_all)
Definition: Simulator.h:471
void AddActorImpulse(rpc::ActorId actor, const geom::Vector3D &impulse)
std::string ShowRecorderCollisions(std::string name, char type1, char type2)
Definition: Simulator.h:475
void SubscribeToSensor(const Sensor &sensor, std::function< void(SharedPtr< sensor::SensorData >)> callback)
Definition: Simulator.cpp:307
void AddActorTorque(const Actor &actor, const geom::Vector3D &torque)
Definition: Simulator.h:391
void DestroyTrafficManager(uint16_t port) const
Definition: Simulator.h:201
std::vector< rpc::CommandResponse > ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue)
rpc::VehicleLightState GetVehicleLightState(const Vehicle &vehicle) const
Definition: Simulator.h:235
void SetTrafficLightRedTime(rpc::ActorId traffic_light, float red_time)
rpc::VehicleLightState GetVehicleLightState(rpc::ActorId vehicle) const
geom::Vector3D GetActorAngularVelocity(const Actor &actor) const
Definition: Simulator.h:356
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:309
void UpdateServerLightsState(std::vector< rpc::LightState > &lights, bool discard_client=false) const
void SetTimeout(time_duration timeout)
void SetActorTargetAngularVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
GarbageCollectionPolicy GetGarbageCollectionPolicy() const
Definition: Simulator.h:129
void SetActorEnableGravity(Actor &actor, bool enabled)
Definition: Simulator.h:411
Provides communication with the rpc and streaming servers of a CARLA simulator.
WorldSnapshot GetWorldSnapshot() const
Definition: Simulator.h:106
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id)
Definition: Simulator.h:483
void SetNetworkingTimeout(time_duration timeout)
Definition: Simulator.h:139
size_t RegisterLightUpdateChangeEvent(std::function< void(WorldSnapshot)> callback)
Definition: Simulator.h:593
void UnloadLevelLayer(rpc::MapLayer map_layer) const
void UnregisterAIController(const WalkerAIController &controller)
Definition: Simulator.cpp:230
void SetActorSimulatePhysics(rpc::ActorId actor, bool enabled)
std::vector< rpc::LightState > QueryLightsStateToServer() const
std::shared_ptr< WalkerNavigation > GetNavigation()
Definition: Simulator.h:276
void UseCarSimRoad(rpc::ActorId vehicle, bool enabled)
uint64_t Tick(time_duration timeout)
Definition: Simulator.cpp:158
SharedPtr< Map > GetCurrentMap()
Definition: Simulator.cpp:141
void SetWeatherParameters(const rpc::WeatherParameters &weather)
void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control)
Definition: Simulator.h:433
EpisodeProxy LoadOpenDriveEpisode(std::string opendrive, const rpc::OpendriveGenerationParameters &params, bool reset_settings=true)
Definition: Simulator.cpp:113
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id)
Represents an actor in the simulation.
Definition: client/Actor.h:18
geom::Vector3D angular_velocity
Definition: ActorSnapshot.h:21
void SetReplayerIgnoreHero(bool ignore_hero)
Definition: Simulator.h:491
void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state)
Definition: Simulator.h:445
std::pair< std::string, uint16_t > GetTrafficManagerRunning(uint16_t port) const
Gets a pair filled with the <IP, port> of the Trafic Manager running on port.
Definition: Simulator.h:192
Positive time duration up to milliseconds resolution.
Definition: Time.h:19
geom::Location GetActorLocation(const Actor &actor) const
Definition: Simulator.h:340
void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime)
Definition: Simulator.h:525
void SetTrafficLightGreenTime(rpc::ActorId traffic_light, float green_time)
void SetActorTransform(Actor &actor, const geom::Transform &transform)
Definition: Simulator.h:403
std::string ShowRecorderCollisions(std::string name, char type1, char type2)
std::vector< rpc::EnvironmentObject > GetEnvironmentObjects(uint8_t queried_tag) const
std::vector< rpc::Actor > GetAllTheActorsInTheEpisode() const
Definition: Simulator.h:298
void UnloadLevelLayer(rpc::MapLayer map_layers) const
Definition: Simulator.h:77
Contains all the necessary information for spawning an Actor.
void RegisterAIController(const WalkerAIController &controller)
Definition: Simulator.cpp:218
geom::Vector3D GetActorAcceleration(const Actor &actor) const
Definition: Simulator.h:395
void SetActorEnableGravity(rpc::ActorId actor, bool enabled)
void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location)
Definition: Simulator.h:375
void SetPedestriansCrossFactor(float percentage)
Definition: Simulator.cpp:249
SharedPtr< BlueprintLibrary > GetBlueprintLibrary()
Definition: Simulator.cpp:172
std::pair< bool, rpc::LabelledPoint > ProjectPoint(geom::Location location, geom::Vector3D direction, float search_distance) const
void AddActorForce(rpc::ActorId actor, const geom::Vector3D &force)
ActorSnapshot GetActorSnapshot(const Actor &actor) const
Definition: Simulator.h:336
geom::Vector3D GetActorVelocity(const Actor &actor) const
Definition: Simulator.h:348
auto ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition: Simulator.h:569
Inherit (privately) to suppress copy/move construction and assignment.
void AddActorForce(const Actor &actor, const geom::Vector3D &force, const geom::Vector3D &location)
Definition: Simulator.h:383
Defines the physical appearance of a vehicle whitch is obtained by the sensors.
void ApplyControlToWalker(rpc::ActorId walker, const rpc::WalkerControl &control)
std::string StartRecorder(std::string name, bool additional_data)
Definition: Simulator.h:463
const std::string GetEndpoint() const
void ApplyPhysicsControlToVehicle(Vehicle &vehicle, const rpc::VehiclePhysicsControl &physicsControl)
Definition: Simulator.h:441
void EnableEnvironmentObjects(std::vector< uint64_t > env_objects_ids, bool enable) const
void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition: Simulator.h:352
rpc::WeatherParameters GetWeatherParameters()
Definition: Simulator.h:223
void LoadLevelLayer(rpc::MapLayer map_layers) const
Definition: Simulator.h:73
void ResetTrafficLightGroup(TrafficLight &trafficLight)
Definition: Simulator.h:537
WorldSnapshot WaitForTick(time_duration timeout)
Definition: Simulator.cpp:149
bool IsTrafficManagerRunning(uint16_t port) const
Query to know if a Traffic Manager is running on port.
Definition: Simulator.h:186
void SetReplayerTimeFactor(double time_factor)
Definition: Simulator.h:487
void DisableActorConstantVelocity(rpc::ActorId actor)
std::vector< std::string > GetAvailableMaps()
std::vector< geom::BoundingBox > GetLevelBBs(uint8_t queried_tag) const
Returns all the BBs of all the elements of the level.
Definition: Simulator.h:240
geom::Transform GetActorTransform(const Actor &actor) const
Definition: Simulator.h:344