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/Logging.h"
11 #include "carla/Memory.h"
12 #include "carla/NonCopyable.h"
13 #include "carla/client/Actor.h"
16 #include "carla/client/Vehicle.h"
17 #include "carla/client/Walker.h"
18 #include "carla/client/World.h"
29 #include "carla/rpc/Texture.h"
31 
32 #include <boost/optional.hpp>
33 
34 #include <memory>
35 
36 namespace carla {
37 namespace client {
38 
39  class ActorBlueprint;
40  class BlueprintLibrary;
41  class Map;
42  class Sensor;
43  class WalkerAIController;
44  class WalkerNavigation;
45 
46 namespace detail {
47 
48  /// Connects and controls a CARLA Simulator.
49  class Simulator
50  : public std::enable_shared_from_this<Simulator>,
52  private NonCopyable {
53  public:
54 
55  // =========================================================================
56  /// @name Constructor
57  // =========================================================================
58  /// @{
59 
60  explicit Simulator(
61  const std::string &host,
62  uint16_t port,
63  size_t worker_threads = 0u,
64  bool enable_garbage_collection = false);
65 
66  /// @}
67  // =========================================================================
68  /// @name Load a new episode
69  // =========================================================================
70  /// @{
71 
72  EpisodeProxy ReloadEpisode(bool reset_settings = true) {
73  return LoadEpisode("", reset_settings);
74  }
75 
76  EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings = true, rpc::MapLayer map_layers = rpc::MapLayer::All);
77 
78  void LoadLevelLayer(rpc::MapLayer map_layers) const {
79  _client.LoadLevelLayer(map_layers);
80  }
81 
82  void UnloadLevelLayer(rpc::MapLayer map_layers) const {
83  _client.UnloadLevelLayer(map_layers);
84  }
85 
87  std::string opendrive,
89  bool reset_settings = true);
90 
91  /// @}
92  // =========================================================================
93  /// @name Access to current episode
94  // =========================================================================
95  /// @{
96 
97  /// @pre Cannot be called previous to GetCurrentEpisode.
100  DEBUG_ASSERT(_episode != nullptr);
101  return _episode->GetId();
102  }
103 
104  void GetReadyCurrentEpisode();
106 
107  /// @}
108  // =========================================================================
109  /// @name World snapshot
110  // =========================================================================
111  /// @{
112 
114  return World{GetCurrentEpisode()};
115  }
116 
117  /// @}
118  // =========================================================================
119  /// @name World snapshot
120  // =========================================================================
121  /// @{
122 
124  DEBUG_ASSERT(_episode != nullptr);
125  return WorldSnapshot{_episode->GetState()};
126  }
127 
128  /// @}
129  // =========================================================================
130  /// @name Map related methods
131  // =========================================================================
132  /// @{
133 
135 
136  std::vector<std::string> GetAvailableMaps() {
137  return _client.GetAvailableMaps();
138  }
139 
140  /// @}
141  // =========================================================================
142  /// @name Required files related methods
143  // =========================================================================
144  /// @{
145 
146  bool SetFilesBaseFolder(const std::string &path);
147 
148  std::vector<std::string> GetRequiredFiles(const std::string &folder = "", const bool download = true) const;
149 
150  void RequestFile(const std::string &name) const;
151 
152  std::vector<uint8_t> GetCacheFile(const std::string &name, const bool request_otherwise) const;
153 
154  /// @}
155  // =========================================================================
156  /// @name Garbage collection policy
157  // =========================================================================
158  /// @{
159 
161  return _gc_policy;
162  }
163 
164  /// @}
165  // =========================================================================
166  /// @name Pure networking operations
167  // =========================================================================
168  /// @{
169 
171  _client.SetTimeout(timeout);
172  }
173 
175  return _client.GetTimeout();
176  }
177 
178  std::string GetClientVersion() {
179  return _client.GetClientVersion();
180  }
181 
182  std::string GetServerVersion() {
183  return _client.GetServerVersion();
184  }
185 
186  /// @}
187  // =========================================================================
188  /// @name Tick
189  // =========================================================================
190  /// @{
191 
193 
194  size_t RegisterOnTickEvent(std::function<void(WorldSnapshot)> callback) {
195  DEBUG_ASSERT(_episode != nullptr);
196  return _episode->RegisterOnTickEvent(std::move(callback));
197  }
198 
199  void RemoveOnTickEvent(size_t id) {
200  DEBUG_ASSERT(_episode != nullptr);
201  _episode->RemoveOnTickEvent(id);
202  }
203 
204  uint64_t Tick(time_duration timeout);
205 
206  /// @}
207  // =========================================================================
208  /// @name Access to global objects in the episode
209  // =========================================================================
210  /// @{
211 
212  std :: string GetEndpoint() {
213  return _client.GetEndpoint();
214  }
215 
216  /// Query to know if a Traffic Manager is running on port
217  bool IsTrafficManagerRunning(uint16_t port) const {
218  return _client.IsTrafficManagerRunning(port);
219  }
220 
221  /// Gets a pair filled with the <IP, port> of the Trafic Manager running on port.
222  /// If there is no Traffic Manager running the pair will be ("", 0)
223  std::pair<std::string, uint16_t> GetTrafficManagerRunning(uint16_t port) const {
224  return _client.GetTrafficManagerRunning(port);
225  }
226 
227  /// Informs that a Traffic Manager is running on <IP, port>
228  bool AddTrafficManagerRunning(std::pair<std::string, uint16_t> trafficManagerInfo) const {
229  return _client.AddTrafficManagerRunning(trafficManagerInfo);
230  }
231 
232  void DestroyTrafficManager(uint16_t port) const {
234  }
235 
236  void AddPendingException(std::string e) {
237  _episode->AddPendingException(e);
238  }
239 
241 
242  /// Returns a list of pairs where the firts element is the vehicle ID
243  /// and the second one is the light state
245 
247 
249  return _client.GetEpisodeSettings();
250  }
251 
252  uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings);
253 
255  return _client.GetWeatherParameters();
256  }
257 
259  _client.SetWeatherParameters(weather);
260  }
261 
263  return _client.GetVehiclePhysicsControl(vehicle.GetId());
264  }
265 
267  return _client.GetVehicleLightState(vehicle.GetId());
268  }
269 
270  /// Returns all the BBs of all the elements of the level
271  std::vector<geom::BoundingBox> GetLevelBBs(uint8_t queried_tag) const {
272  return _client.GetLevelBBs(queried_tag);
273  }
274 
275  std::vector<rpc::EnvironmentObject> GetEnvironmentObjects(uint8_t queried_tag) const {
276  return _client.GetEnvironmentObjects(queried_tag);
277  }
278 
280  std::vector<uint64_t> env_objects_ids,
281  bool enable) const {
282  _client.EnableEnvironmentObjects(env_objects_ids, enable);
283  }
284 
285  std::pair<bool,rpc::LabelledPoint> ProjectPoint(
286  geom::Location location, geom::Vector3D direction, float search_distance) const {
287  return _client.ProjectPoint(location, direction, search_distance);
288  }
289 
290  std::vector<rpc::LabelledPoint> CastRay(
291  geom::Location start_location, geom::Location end_location) const {
292  return _client.CastRay(start_location, end_location);
293  }
294 
295  /// @}
296  // =========================================================================
297  /// @name AI
298  // =========================================================================
299  /// @{
300 
301  std::shared_ptr<WalkerNavigation> GetNavigation();
302 
303  void NavigationTick();
304 
305  void RegisterAIController(const WalkerAIController &controller);
306 
307  void UnregisterAIController(const WalkerAIController &controller);
308 
309  boost::optional<geom::Location> GetRandomLocationFromNavigation();
310 
311  void SetPedestriansCrossFactor(float percentage);
312 
313  void SetPedestriansSeed(unsigned int seed);
314 
315  /// @}
316  // =========================================================================
317  /// @name General operations with actors
318  // =========================================================================
319  /// @{
320 
321  boost::optional<rpc::Actor> GetActorById(ActorId id) const {
322  DEBUG_ASSERT(_episode != nullptr);
323  return _episode->GetActorById(id);
324  }
325 
326  std::vector<rpc::Actor> GetActorsById(const std::vector<ActorId> &actor_ids) const {
327  DEBUG_ASSERT(_episode != nullptr);
328  return _episode->GetActorsById(actor_ids);
329  }
330 
331  std::vector<rpc::Actor> GetAllTheActorsInTheEpisode() const {
332  DEBUG_ASSERT(_episode != nullptr);
333  return _episode->GetActors();
334  }
335 
336  /// Creates an actor instance out of a description of an existing actor.
337  /// Note that this does not spawn an actor.
338  ///
339  /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
340  /// returned is provided with a custom deleter that calls Destroy() on the
341  /// actor. This method does not support GarbageCollectionPolicy::Inherit.
343  rpc::Actor actor_description,
346  return ActorFactory::MakeActor(GetCurrentEpisode(), std::move(actor_description), gc);
347  }
348 
349  /// Spawns an actor into the simulation.
350  ///
351  /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
352  /// returned is provided with a custom deleter that calls Destroy() on the
353  /// actor. If @gc is GarbageCollectionPolicy::Inherit, the default garbage
354  /// collection policy is used.
356  const ActorBlueprint &blueprint,
357  const geom::Transform &transform,
358  Actor *parent = nullptr,
361 
362  bool DestroyActor(Actor &actor);
363 
364  bool DestroyActor(ActorId actor_id)
365  {
366  return _client.DestroyActor(actor_id);
367  }
368 
370  DEBUG_ASSERT(_episode != nullptr);
371  return _episode->GetState()->GetActorSnapshot(actor_id);
372  }
373 
374  ActorSnapshot GetActorSnapshot(const Actor &actor) const {
375  return GetActorSnapshot(actor.GetId());
376  }
377 
378  rpc::ActorState GetActorState(const Actor &actor) const {
379  return GetActorSnapshot(actor).actor_state;
380  }
381 
382  geom::Location GetActorLocation(const Actor &actor) const {
383  return GetActorSnapshot(actor).transform.location;
384  }
385 
387  return GetActorSnapshot(actor).transform;
388  }
389 
390  geom::Vector3D GetActorVelocity(const Actor &actor) const {
391  return GetActorSnapshot(actor).velocity;
392  }
393 
394  void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector) {
395  _client.SetActorTargetVelocity(actor.GetId(), vector);
396  }
397 
399  return GetActorSnapshot(actor).angular_velocity;
400  }
401 
402  void SetActorTargetAngularVelocity(const Actor &actor, const geom::Vector3D &vector) {
404  }
405  void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector) {
406  _client.EnableActorConstantVelocity(actor.GetId(), vector);
407  }
408 
409  void DisableActorConstantVelocity(const Actor &actor) {
411  }
412 
413  void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse) {
414  _client.AddActorImpulse(actor.GetId(), impulse);
415  }
416 
417  void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location) {
418  _client.AddActorImpulse(actor.GetId(), impulse, location);
419  }
420 
421  void AddActorForce(const Actor &actor, const geom::Vector3D &force) {
422  _client.AddActorForce(actor.GetId(), force);
423  }
424 
425  void AddActorForce(const Actor &actor, const geom::Vector3D &force, const geom::Vector3D &location) {
426  _client.AddActorForce(actor.GetId(), force, location);
427  }
428 
429  void AddActorAngularImpulse(const Actor &actor, const geom::Vector3D &vector) {
430  _client.AddActorAngularImpulse(actor.GetId(), vector);
431  }
432 
433  void AddActorTorque(const Actor &actor, const geom::Vector3D &torque) {
434  _client.AddActorAngularImpulse(actor.GetId(), torque);
435  }
436 
438  return GetActorSnapshot(actor).acceleration;
439  }
440 
441  void SetActorLocation(Actor &actor, const geom::Location &location) {
442  _client.SetActorLocation(actor.GetId(), location);
443  }
444 
445  void SetActorTransform(Actor &actor, const geom::Transform &transform) {
446  _client.SetActorTransform(actor.GetId(), transform);
447  }
448 
449  void SetActorSimulatePhysics(Actor &actor, bool enabled) {
450  _client.SetActorSimulatePhysics(actor.GetId(), enabled);
451  }
452 
453  void SetActorCollisions(Actor &actor, bool enabled) {
454  _client.SetActorCollisions(actor.GetId(), enabled);
455  }
456 
457  void SetActorCollisions(ActorId actor_id, bool enabled) {
458  _client.SetActorCollisions(actor_id, enabled);
459  }
460 
461  void SetActorDead(Actor &actor) {
462  _client.SetActorDead(actor.GetId());
463  }
464 
465  void SetActorDead(ActorId actor_id) {
466  _client.SetActorDead(actor_id);
467  }
468 
469  void SetActorEnableGravity(Actor &actor, bool enabled) {
470  _client.SetActorEnableGravity(actor.GetId(), enabled);
471  }
472 
473  /// @}
474  // =========================================================================
475  /// @name Operations with vehicles
476  // =========================================================================
477  /// @{
478 
479  void SetVehicleAutopilot(Vehicle &vehicle, bool enabled = true) {
480  _client.SetActorAutopilot(vehicle.GetId(), enabled);
481  }
482 
483  void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled = true) {
484  _client.ShowVehicleDebugTelemetry(vehicle.GetId(), enabled);
485  }
486 
487  void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
488  _client.ApplyControlToVehicle(vehicle.GetId(), control);
489  }
490 
491  void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
492  _client.ApplyControlToVehicle(vehicle.GetId(), control);
493  }
494 
496  _client.ApplyAckermannControlToVehicle(vehicle.GetId(), control);
497  }
498 
500  return _client.GetAckermannControllerSettings(vehicle.GetId());
501  }
502 
504  _client.ApplyAckermannControllerSettings(vehicle.GetId(), settings);
505  }
506 
507  void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control) {
508  _client.ApplyControlToWalker(walker.GetId(), control);
509  }
510 
512  return _client.GetBonesTransform(walker.GetId());
513  }
514 
515  void SetBonesTransform(Walker &walker, const rpc::WalkerBoneControlIn &bones) {
516  return _client.SetBonesTransform(walker.GetId(), bones);
517  }
518 
519  void BlendPose(Walker &walker, float blend) {
520  return _client.BlendPose(walker.GetId(), blend);
521  }
522 
523  void GetPoseFromAnimation(Walker &walker) {
524  return _client.GetPoseFromAnimation(walker.GetId());
525  }
526 
527  void ApplyPhysicsControlToVehicle(Vehicle &vehicle, const rpc::VehiclePhysicsControl &physicsControl) {
528  _client.ApplyPhysicsControlToVehicle(vehicle.GetId(), physicsControl);
529  }
530 
531  void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state) {
532  _client.SetLightStateToVehicle(vehicle.GetId(), light_state);
533  }
534 
535  void OpenVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx) {
536  _client.OpenVehicleDoor(vehicle.GetId(), door_idx);
537  }
538 
539  void CloseVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx) {
540  _client.CloseVehicleDoor(vehicle.GetId(), door_idx);
541  }
542 
543  void SetWheelSteerDirection(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location, float angle_in_deg) {
544  _client.SetWheelSteerDirection(vehicle.GetId(), wheel_location, angle_in_deg);
545  }
546 
547  float GetWheelSteerAngle(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location) {
548  return _client.GetWheelSteerAngle(vehicle.GetId(), wheel_location);
549  }
550 
551  void EnableCarSim(Vehicle &vehicle, std::string simfile_path) {
552  _client.EnableCarSim(vehicle.GetId(), simfile_path);
553  }
554 
555  void UseCarSimRoad(Vehicle &vehicle, bool enabled) {
556  _client.UseCarSimRoad(vehicle.GetId(), enabled);
557  }
558 
560  uint64_t MaxSubsteps,
561  float MaxSubstepDeltaTime,
562  std::string VehicleJSON,
563  std::string PowertrainJSON,
564  std::string TireJSON,
565  std::string BaseJSONPath) {
567  MaxSubsteps,
568  MaxSubstepDeltaTime,
569  VehicleJSON,
570  PowertrainJSON,
571  TireJSON,
572  BaseJSONPath);
573  }
574 
575  /// @}
576  // =========================================================================
577  /// @name Operations with the recorder
578  // =========================================================================
579  /// @{
580 
581  std::string StartRecorder(std::string name, bool additional_data) {
582  return _client.StartRecorder(std::move(name), additional_data);
583  }
584 
585  void StopRecorder(void) {
587  }
588 
589  std::string ShowRecorderFileInfo(std::string name, bool show_all) {
590  return _client.ShowRecorderFileInfo(std::move(name), show_all);
591  }
592 
593  std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
594  return _client.ShowRecorderCollisions(std::move(name), type1, type2);
595  }
596 
597  std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
598  return _client.ShowRecorderActorsBlocked(std::move(name), min_time, min_distance);
599  }
600 
601  std::string ReplayFile(std::string name, double start, double duration,
602  uint32_t follow_id, bool replay_sensors) {
603  return _client.ReplayFile(std::move(name), start, duration, follow_id, replay_sensors);
604  }
605 
606  void SetReplayerTimeFactor(double time_factor) {
607  _client.SetReplayerTimeFactor(time_factor);
608  }
609 
610  void SetReplayerIgnoreHero(bool ignore_hero) {
611  _client.SetReplayerIgnoreHero(ignore_hero);
612  }
613 
614  void SetReplayerIgnoreSpectator(bool ignore_spectator) {
615  _client.SetReplayerIgnoreSpectator(ignore_spectator);
616  }
617 
618  void StopReplayer(bool keep_actors) {
619  _client.StopReplayer(keep_actors);
620  }
621 
622  /// @}
623  // =========================================================================
624  /// @name Operations with sensors
625  // =========================================================================
626  /// @{
627 
628  void SubscribeToSensor(
629  const Sensor &sensor,
630  std::function<void(SharedPtr<sensor::SensorData>)> callback);
631 
632  void UnSubscribeFromSensor(Actor &sensor);
633 
634  void EnableForROS(const Sensor &sensor);
635 
636  void DisableForROS(const Sensor &sensor);
637 
638  bool IsEnabledForROS(const Sensor &sensor);
639 
640  void SubscribeToGBuffer(
641  Actor & sensor,
642  uint32_t gbuffer_id,
643  std::function<void(SharedPtr<sensor::SensorData>)> callback);
644 
646  Actor & sensor,
647  uint32_t gbuffer_id);
648 
649  /// @}
650  // =========================================================================
651  /// @name Operations with traffic lights
652  // =========================================================================
653  /// @{
654 
655  void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState) {
656  _client.SetTrafficLightState(trafficLight.GetId(), trafficLightState);
657  }
658 
659  void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime) {
660  _client.SetTrafficLightGreenTime(trafficLight.GetId(), greenTime);
661  }
662 
663  void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime) {
664  _client.SetTrafficLightYellowTime(trafficLight.GetId(), yellowTime);
665  }
666 
667  void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime) {
668  _client.SetTrafficLightRedTime(trafficLight.GetId(), redTime);
669  }
670 
671  void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze) {
672  _client.FreezeTrafficLight(trafficLight.GetId(), freeze);
673  }
674 
675  void ResetTrafficLightGroup(TrafficLight &trafficLight) {
676  _client.ResetTrafficLightGroup(trafficLight.GetId());
677  }
678 
681  }
682 
683  std::vector<geom::BoundingBox> GetLightBoxes(const TrafficLight &trafficLight) const {
684  return _client.GetLightBoxes(trafficLight.GetId());
685  }
686 
687  std::vector<ActorId> GetGroupTrafficLights(TrafficLight &trafficLight) {
688  return _client.GetGroupTrafficLights(trafficLight.GetId());
689  }
690 
691  /// @}
692  // =========================================================================
693  /// @name Debug
694  // =========================================================================
695  /// @{
696 
697  void DrawDebugShape(const rpc::DebugShape &shape) {
698  _client.DrawDebugShape(shape);
699  }
700 
701  /// @}
702  // =========================================================================
703  /// @name Apply commands in batch
704  // =========================================================================
705  /// @{
706 
707  void ApplyBatch(std::vector<rpc::Command> commands, bool do_tick_cue) {
708  _client.ApplyBatch(std::move(commands), do_tick_cue);
709  }
710 
711  auto ApplyBatchSync(std::vector<rpc::Command> commands, bool do_tick_cue) {
712  return _client.ApplyBatchSync(std::move(commands), do_tick_cue);
713  }
714 
715  /// @}
716  // =========================================================================
717  /// @name Operations lights
718  // =========================================================================
719  /// @{
720 
722  return _light_manager;
723  }
724 
725  std::vector<rpc::LightState> QueryLightsStateToServer() const {
727  }
728 
730  std::vector<rpc::LightState>& lights,
731  bool discard_client = false) const {
732  _client.UpdateServerLightsState(lights, discard_client);
733  }
734 
735  void UpdateDayNightCycle(const bool active) const {
737  }
738 
739  size_t RegisterLightUpdateChangeEvent(std::function<void(WorldSnapshot)> callback) {
740  DEBUG_ASSERT(_episode != nullptr);
741  return _episode->RegisterLightUpdateChangeEvent(std::move(callback));
742  }
743 
745  DEBUG_ASSERT(_episode != nullptr);
746  _episode->RemoveLightUpdateChangeEvent(id);
747  }
748 
749  void FreezeAllTrafficLights(bool frozen);
750 
751  /// @}
752  // =========================================================================
753  /// @name Texture updating operations
754  // =========================================================================
755  /// @{
756 
758  const std::vector<std::string> &objects_name,
759  const rpc::MaterialParameter& parameter,
760  const rpc::TextureColor& Texture);
761 
763  const std::vector<std::string> &objects_name,
764  const rpc::MaterialParameter& parameter,
765  const rpc::TextureFloatColor& Texture);
766 
767  std::vector<std::string> GetNamesOfAllObjects() const;
768 
769  /// @}
770 
771  private:
772 
773  bool ShouldUpdateMap(rpc::MapInfo& map_info);
774 
776 
778 
779  std::shared_ptr<Episode> _episode;
780 
782 
784 
785  std::string _open_drive_file;
786  };
787 
788 } // namespace detail
789 } // namespace client
790 } // namespace carla
void DisableActorConstantVelocity(const Actor &actor)
Definition: Simulator.h:409
void SetVehicleAutopilot(Vehicle &vehicle, bool enabled=true)
Definition: Simulator.h:479
void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition: Simulator.h:405
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::vector< geom::BoundingBox > GetLightBoxes(const TrafficLight &trafficLight) const
Definition: Simulator.h:683
std::shared_ptr< Episode > _episode
Definition: Simulator.h:779
bool DestroyActor(Actor &actor)
Definition: Simulator.cpp:375
time_duration GetNetworkingTimeout()
Definition: Simulator.h:174
void AddPendingException(std::string e)
Definition: Simulator.h:236
boost::optional< rpc::Actor > GetActorById(ActorId id) const
Definition: Simulator.h:321
void ApplyAckermannControllerSettings(rpc::ActorId vehicle, const rpc::AckermannControllerSettings &settings)
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:413
void EnableChronoPhysics(Vehicle &vehicle, uint64_t MaxSubsteps, float MaxSubstepDeltaTime, std::string VehicleJSON, std::string PowertrainJSON, std::string TireJSON, std::string BaseJSONPath)
Definition: Simulator.h:559
bool DestroyActor(ActorId actor_id)
Definition: Simulator.h:364
std::vector< rpc::LabelledPoint > CastRay(geom::Location start_location, geom::Location end_location) const
Definition: Simulator.h:290
std::vector< rpc::Actor > GetActorsById(const std::vector< ActorId > &actor_ids) const
Definition: Simulator.h:326
void ApplyAckermannControlToVehicle(rpc::ActorId vehicle, const rpc::VehicleAckermannControl &control)
bool SetFilesBaseFolder(const std::string &path)
Definition: Simulator.cpp:188
void SetActorTargetVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
void SetActorDead(Actor &actor)
Definition: Simulator.h:461
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)
void SetBonesTransform(rpc::ActorId walker, const rpc::WalkerBoneControlIn &bones)
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:228
ActorSnapshot GetActorSnapshot(ActorId actor_id) const
Definition: Simulator.h:369
std::vector< rpc::LightState > QueryLightsStateToServer() const
Definition: Simulator.h:725
void ShowVehicleDebugTelemetry(rpc::ActorId vehicle, bool enabled)
std::shared_ptr< WalkerNavigation > GetNavigation()
Definition: Simulator.cpp:288
void SetActorSimulatePhysics(Actor &actor, bool enabled)
Definition: Simulator.h:449
std::vector< std::string > GetAvailableMaps()
Definition: Simulator.h:136
void CloseVehicleDoor(rpc::ActorId vehicle, const rpc::VehicleDoor door_idx)
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:729
void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState)
Definition: Simulator.h:655
rpc::VehiclePhysicsControl GetVehiclePhysicsControl(const Vehicle &vehicle) const
Definition: Simulator.h:262
void SetActorTransform(rpc::ActorId actor, const geom::Transform &transform)
void GetPoseFromAnimation(rpc::ActorId walker)
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id, bool replay_sensors)
SharedPtr< LightManager > GetLightManager() const
Definition: Simulator.h:721
bool IsEnabledForROS(const Sensor &sensor)
Definition: Simulator.cpp:418
void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled=true)
Definition: Simulator.h:483
void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition: Simulator.h:491
rpc::AckermannControllerSettings GetAckermannControllerSettings(const Vehicle &vehicle) const
Definition: Simulator.h:499
void SetActorCollisions(rpc::ActorId actor, bool enabled)
std::vector< ActorId > GetGroupTrafficLights(rpc::ActorId traffic_light)
float GetWheelSteerAngle(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location)
Definition: Simulator.h:547
rpc::AckermannControllerSettings GetAckermannControllerSettings(rpc::ActorId vehicle) const
std::vector< std::string > GetNamesOfAllObjects() const
Definition: Simulator.cpp:460
void SetTrafficLightYellowTime(rpc::ActorId traffic_light, float yellow_time)
std::vector< uint8_t > GetCacheFile(const std::string &name, const bool request_otherwise) const
Definition: Simulator.cpp:200
void OpenVehicleDoor(rpc::ActorId vehicle, const rpc::VehicleDoor door_idx)
void UpdateDayNightCycle(const bool active) const
Definition: Simulator.h:735
void EnableActorConstantVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime)
Definition: Simulator.h:659
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
void SetWeatherParameters(const rpc::WeatherParameters &weather)
Definition: Simulator.h:258
void ApplyAckermannControllerSettings(Vehicle &vehicle, const rpc::AckermannControllerSettings &settings)
Definition: Simulator.h:503
void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition: Simulator.h:487
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
void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze)
Definition: Simulator.h:671
std::vector< std::pair< ActorId, VehicleLightState::flag_type > > VehicleLightStateList
rpc::WalkerBoneControlOut GetBonesTransform(Walker &walker)
Definition: Simulator.h:511
This file contains definitions of common data structures used in traffic manager. ...
Definition: Carla.cpp:133
const GarbageCollectionPolicy _gc_policy
Definition: Simulator.h:781
size_t RegisterOnTickEvent(std::function< void(WorldSnapshot)> callback)
Definition: Simulator.h:194
rpc::EpisodeSettings GetEpisodeSettings()
SharedPtr< Actor > GetSpectator()
Definition: Simulator.cpp:251
void DrawDebugShape(const rpc::DebugShape &shape)
void SetActorDead(rpc::ActorId actor)
void ApplyAckermannControlToVehicle(Vehicle &vehicle, const rpc::VehicleAckermannControl &control)
Definition: Simulator.h:495
boost::optional< geom::Location > GetRandomLocationFromNavigation()
Definition: Simulator.cpp:323
Simulator(const std::string &host, uint16_t port, size_t worker_threads=0u, bool enable_garbage_collection=false)
Definition: Simulator.cpp:72
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
void SetReplayerIgnoreSpectator(bool ignore_spectator)
std::vector< ActorId > GetGroupTrafficLights(TrafficLight &trafficLight)
Definition: Simulator.h:687
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:402
std::vector< rpc::EnvironmentObject > GetEnvironmentObjects(uint8_t queried_tag) const
Definition: Simulator.h:275
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:429
void RemoveOnTickEvent(size_t id)
Definition: Simulator.h:199
void ApplyControlToVehicle(rpc::ActorId vehicle, const rpc::VehicleControl &control)
void EnableForROS(const Sensor &sensor)
Definition: Simulator.cpp:410
void LoadLevelLayer(rpc::MapLayer map_layer) const
SharedPtr< Map > _cached_map
Definition: Simulator.h:783
void ApplyBatch(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition: Simulator.h:707
void GetPoseFromAnimation(Walker &walker)
Definition: Simulator.h:523
void UseCarSimRoad(Vehicle &vehicle, bool enabled)
Definition: Simulator.h:555
void StopReplayer(bool keep_actors)
Definition: Simulator.h:618
void SetActorCollisions(Actor &actor, bool enabled)
Definition: Simulator.h:453
void SetActorLocation(Actor &actor, const geom::Location &location)
Definition: Simulator.h:441
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
Definition: Simulator.h:597
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)
Definition: Simulator.cpp:255
void DrawDebugShape(const rpc::DebugShape &shape)
Definition: Simulator.h:697
#define DEBUG_ASSERT(predicate)
Definition: Debug.h:66
rpc::EpisodeSettings GetEpisodeSettings()
Definition: Simulator.h:248
std::vector< rpc::LabelledPoint > CastRay(geom::Location start_location, geom::Location end_location) const
void RemoveLightUpdateChangeEvent(size_t id)
Definition: Simulator.h:744
void SetReplayerTimeFactor(double time_factor)
std::pair< bool, rpc::LabelledPoint > ProjectPoint(geom::Location location, geom::Vector3D direction, float search_distance) const
Definition: Simulator.h:285
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:345
std::string StartRecorder(std::string name, bool additional_data)
Connects and controls a CARLA Simulator.
Definition: Simulator.h:49
rpc::WeatherParameters GetWeatherParameters()
void BlendPose(Walker &walker, float blend)
Definition: Simulator.h:519
void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime)
Definition: Simulator.h:667
rpc::ActorState GetActorState(const Actor &actor) const
Definition: Simulator.h:378
void EnableCarSim(Vehicle &vehicle, std::string simfile_path)
Definition: Simulator.h:551
void FreezeAllTrafficLights(bool frozen)
Definition: Simulator.cpp:438
void EnableEnvironmentObjects(std::vector< uint64_t > env_objects_ids, bool enable) const
Definition: Simulator.h:279
void BlendPose(rpc::ActorId walker, float blend)
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:421
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 EnableChronoPhysics(rpc::ActorId vehicle, uint64_t MaxSubsteps, float MaxSubstepDeltaTime, std::string VehicleJSON, std::string PowertrainJSON, std::string TireJSON, std::string BaseJSONPath)
#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 OpenVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx)
Definition: Simulator.h:535
float GetWheelSteerAngle(rpc::ActorId vehicle, rpc::VehicleWheelLocation wheel_location)
void DestroyTrafficManager(uint16_t port) const
carla::ActorId ActorId
EpisodeProxy ReloadEpisode(bool reset_settings=true)
Definition: Simulator.h:72
std::string ShowRecorderFileInfo(std::string name, bool show_all)
Definition: Simulator.h:589
void AddActorImpulse(rpc::ActorId actor, const geom::Vector3D &impulse)
std::string ShowRecorderCollisions(std::string name, char type1, char type2)
Definition: Simulator.h:593
void SubscribeToSensor(const Sensor &sensor, std::function< void(SharedPtr< sensor::SensorData >)> callback)
Definition: Simulator.cpp:392
void AddActorTorque(const Actor &actor, const geom::Vector3D &torque)
Definition: Simulator.h:433
void DestroyTrafficManager(uint16_t port) const
Definition: Simulator.h:232
std::vector< rpc::CommandResponse > ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue)
rpc::VehicleLightState GetVehicleLightState(const Vehicle &vehicle) const
Definition: Simulator.h:266
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:398
void UnSubscribeFromSensor(Actor &sensor)
Definition: Simulator.cpp:405
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
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:160
void SetActorEnableGravity(Actor &actor, bool enabled)
Definition: Simulator.h:469
Provides communication with the rpc and streaming servers of a CARLA simulator.
WorldSnapshot GetWorldSnapshot() const
Definition: Simulator.h:123
void SetNetworkingTimeout(time_duration timeout)
Definition: Simulator.h:170
void UpdateDayNightCycle(const bool active) const
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id, bool replay_sensors)
Definition: Simulator.h:601
size_t RegisterLightUpdateChangeEvent(std::function< void(WorldSnapshot)> callback)
Definition: Simulator.h:739
void CloseVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx)
Definition: Simulator.h:539
void UnloadLevelLayer(rpc::MapLayer map_layer) const
void UnregisterAIController(const WalkerAIController &controller)
Definition: Simulator.cpp:312
void DisableForROS(const Sensor &sensor)
Definition: Simulator.cpp:414
void SetActorSimulatePhysics(rpc::ActorId actor, bool enabled)
std::vector< rpc::LightState > QueryLightsStateToServer() const
void UseCarSimRoad(rpc::ActorId vehicle, bool enabled)
void SetReplayerIgnoreSpectator(bool ignore_spectator)
Definition: Simulator.h:614
uint64_t Tick(time_duration timeout)
Definition: Simulator.cpp:221
SharedPtr< Map > GetCurrentMap()
Definition: Simulator.cpp:157
bool DestroyActor(rpc::ActorId actor)
void SetWeatherParameters(const rpc::WeatherParameters &weather)
void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control)
Definition: Simulator.h:507
EpisodeProxy LoadOpenDriveEpisode(std::string opendrive, const rpc::OpendriveGenerationParameters &params, bool reset_settings=true)
Definition: Simulator.cpp:115
Represents an actor in the simulation.
Definition: client/Actor.h:18
rpc::WalkerBoneControlOut GetBonesTransform(rpc::ActorId walker)
geom::Vector3D angular_velocity
Definition: ActorSnapshot.h:23
void SetActorCollisions(ActorId actor_id, bool enabled)
Definition: Simulator.h:457
void SetReplayerIgnoreHero(bool ignore_hero)
Definition: Simulator.h:610
void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state)
Definition: Simulator.h:531
void RequestFile(const std::string &name) const
Definition: Simulator.cpp:196
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:223
Positive time duration up to milliseconds resolution.
Definition: Time.h:19
geom::Location GetActorLocation(const Actor &actor) const
Definition: Simulator.h:382
std::vector< geom::BoundingBox > GetLightBoxes(rpc::ActorId traffic_light) const
void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime)
Definition: Simulator.h:663
void SetTrafficLightGreenTime(rpc::ActorId traffic_light, float green_time)
void SetActorTransform(Actor &actor, const geom::Transform &transform)
Definition: Simulator.h:445
void SetBonesTransform(Walker &walker, const rpc::WalkerBoneControlIn &bones)
Definition: Simulator.h:515
void SetWheelSteerDirection(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location, float angle_in_deg)
Definition: Simulator.h:543
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:331
void UnloadLevelLayer(rpc::MapLayer map_layers) const
Definition: Simulator.h:82
Contains all the necessary information for spawning an Actor.
void RegisterAIController(const WalkerAIController &controller)
Definition: Simulator.cpp:301
geom::Vector3D GetActorAcceleration(const Actor &actor) const
Definition: Simulator.h:437
void SetActorEnableGravity(rpc::ActorId actor, bool enabled)
void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location)
Definition: Simulator.h:417
void SetPedestriansCrossFactor(float percentage)
Definition: Simulator.cpp:329
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
void SetActorDead(ActorId actor_id)
Definition: Simulator.h:465
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:374
geom::Vector3D GetActorVelocity(const Actor &actor) const
Definition: Simulator.h:390
void SetWheelSteerDirection(rpc::ActorId vehicle, rpc::VehicleWheelLocation vehicle_wheel, float angle_in_deg)
auto ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition: Simulator.h:711
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:425
Defines the physical appearance of a vehicle whitch is obtained by the sensors.
void ApplyControlToWalker(rpc::ActorId walker, const rpc::WalkerControl &control)
void UnSubscribeFromGBuffer(Actor &sensor, uint32_t gbuffer_id)
Definition: Simulator.cpp:434
bool ShouldUpdateMap(rpc::MapInfo &map_info)
Definition: Simulator.cpp:146
std::string StartRecorder(std::string name, bool additional_data)
Definition: Simulator.h:581
const std::string GetEndpoint() const
void ApplyPhysicsControlToVehicle(Vehicle &vehicle, const rpc::VehiclePhysicsControl &physicsControl)
Definition: Simulator.h:527
void EnableEnvironmentObjects(std::vector< uint64_t > env_objects_ids, bool enable) const
void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition: Simulator.h:394
rpc::WeatherParameters GetWeatherParameters()
Definition: Simulator.h:254
void LoadLevelLayer(rpc::MapLayer map_layers) const
Definition: Simulator.h:78
void SetPedestriansSeed(unsigned int seed)
Definition: Simulator.cpp:335
void ResetTrafficLightGroup(TrafficLight &trafficLight)
Definition: Simulator.h:675
WorldSnapshot WaitForTick(time_duration timeout)
Definition: Simulator.cpp:208
bool IsTrafficManagerRunning(uint16_t port) const
Query to know if a Traffic Manager is running on port.
Definition: Simulator.h:217
void SetReplayerTimeFactor(double time_factor)
Definition: Simulator.h:606
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:271
geom::Transform GetActorTransform(const Actor &actor) const
Definition: Simulator.h:386