CARLA
 
载入中...
搜索中...
未找到
Simulator.h
浏览该文件的文档.
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"
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
36namespace carla {
37namespace client {
38
39 class ActorBlueprint;
40 class BlueprintLibrary;
41 class Map;
42 class Sensor;
43 class WalkerAIController;
44 class WalkerNavigation;
45
46namespace detail {
47
48 /// Connects and controls a CARLA 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
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
163
164 /// @}
165 // =========================================================================
166 /// @name Pure networking operations
167 // =========================================================================
168 /// @{
169
171 _client.SetTimeout(timeout);
172 }
173
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 {
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
251
252 uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings);
253
257
261
262 float GetIMUISensorGravity() const {
264 }
265
266 void SetIMUISensorGravity(float NewIMUISensorGravity) {
267 _client.SetIMUISensorGravity(NewIMUISensorGravity);
268 }
269
273
275 return _client.GetVehicleLightState(vehicle.GetId());
276 }
277
278 /// Returns all the BBs of all the elements of the level
279 std::vector<geom::BoundingBox> GetLevelBBs(uint8_t queried_tag) const {
280 return _client.GetLevelBBs(queried_tag);
281 }
282
283 std::vector<rpc::EnvironmentObject> GetEnvironmentObjects(uint8_t queried_tag) const {
284 return _client.GetEnvironmentObjects(queried_tag);
285 }
286
288 std::vector<uint64_t> env_objects_ids,
289 bool enable) const {
290 _client.EnableEnvironmentObjects(env_objects_ids, enable);
291 }
292
293 std::pair<bool,rpc::LabelledPoint> ProjectPoint(
294 geom::Location location, geom::Vector3D direction, float search_distance) const {
295 return _client.ProjectPoint(location, direction, search_distance);
296 }
297
298 std::vector<rpc::LabelledPoint> CastRay(
299 geom::Location start_location, geom::Location end_location) const {
300 return _client.CastRay(start_location, end_location);
301 }
302
303 /// @}
304 // =========================================================================
305 /// @name AI
306 // =========================================================================
307 /// @{
308
309 std::shared_ptr<WalkerNavigation> GetNavigation();
310
311 void NavigationTick();
312
313 void RegisterAIController(const WalkerAIController &controller);
314
315 void UnregisterAIController(const WalkerAIController &controller);
316
317 boost::optional<geom::Location> GetRandomLocationFromNavigation();
318
319 void SetPedestriansCrossFactor(float percentage);
320
321 void SetPedestriansSeed(unsigned int seed);
322
323 /// @}
324 // =========================================================================
325 /// @name General operations with actors
326 // =========================================================================
327 /// @{
328
329 boost::optional<rpc::Actor> GetActorById(ActorId id) const {
330 DEBUG_ASSERT(_episode != nullptr);
331 return _episode->GetActorById(id);
332 }
333
334 std::vector<rpc::Actor> GetActorsById(const std::vector<ActorId> &actor_ids) const {
335 DEBUG_ASSERT(_episode != nullptr);
336 return _episode->GetActorsById(actor_ids);
337 }
338
339 std::vector<rpc::Actor> GetAllTheActorsInTheEpisode() const {
340 DEBUG_ASSERT(_episode != nullptr);
341 return _episode->GetActors();
342 }
343
344 /// Creates an actor instance out of a description of an existing actor.
345 /// Note that this does not spawn an actor.
346 ///
347 /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
348 /// returned is provided with a custom deleter that calls Destroy() on the
349 /// actor. This method does not support GarbageCollectionPolicy::Inherit.
356
357 /// Spawns an actor into the simulation.
358 ///
359 /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
360 /// returned is provided with a custom deleter that calls Destroy() on the
361 /// actor. If @gc is GarbageCollectionPolicy::Inherit, the default garbage
362 /// collection policy is used.
364 const ActorBlueprint &blueprint,
365 const geom::Transform &transform,
366 Actor *parent = nullptr,
369 const std::string& socket_name = "");
370
371 bool DestroyActor(Actor &actor);
372
373 bool DestroyActor(ActorId actor_id)
374 {
375 return _client.DestroyActor(actor_id);
376 }
377
379 DEBUG_ASSERT(_episode != nullptr);
380 return _episode->GetState()->GetActorSnapshot(actor_id);
381 }
382
384 return GetActorSnapshot(actor.GetId());
385 }
386
387 rpc::ActorState GetActorState(const Actor &actor) const {
388 return GetActorSnapshot(actor).actor_state;
389 }
390
392 return GetActorSnapshot(actor).transform.location;
393 }
394
396 return GetActorSnapshot(actor).transform;
397 }
398
400 return GetActorSnapshot(actor).velocity;
401 }
402
403 void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector) {
404 _client.SetActorTargetVelocity(actor.GetId(), vector);
405 }
406
409 }
410
411 void SetActorTargetAngularVelocity(const Actor &actor, const geom::Vector3D &vector) {
413 }
414 void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector) {
416 }
417
421
422 void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse) {
423 _client.AddActorImpulse(actor.GetId(), impulse);
424 }
425
426 void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location) {
427 _client.AddActorImpulse(actor.GetId(), impulse, location);
428 }
429
430 void AddActorForce(const Actor &actor, const geom::Vector3D &force) {
431 _client.AddActorForce(actor.GetId(), force);
432 }
433
434 void AddActorForce(const Actor &actor, const geom::Vector3D &force, const geom::Vector3D &location) {
435 _client.AddActorForce(actor.GetId(), force, location);
436 }
437
438 void AddActorAngularImpulse(const Actor &actor, const geom::Vector3D &vector) {
439 _client.AddActorAngularImpulse(actor.GetId(), vector);
440 }
441
442 void AddActorTorque(const Actor &actor, const geom::Vector3D &torque) {
443 _client.AddActorAngularImpulse(actor.GetId(), torque);
444 }
445
447 return GetActorSnapshot(actor).acceleration;
448 }
449
450 geom::Transform GetActorComponentWorldTransform(const Actor &actor, const std::string componentName) {
451 return _client.GetActorComponentWorldTransform(actor.GetId(), componentName);
452 }
453
454 geom::Transform GetActorComponentRelativeTransform(const Actor &actor, std::string componentName) {
455 return _client.GetActorComponentRelativeTransform(actor.GetId(), componentName);
456 }
457
458 std::vector<geom::Transform> GetActorBoneWorldTransforms(const Actor &actor) {
460 }
461
462 std::vector<geom::Transform> GetActorBoneRelativeTransforms(const Actor &actor) {
464 }
465
466 std::vector<std::string> GetActorComponentNames(const Actor &actor) {
467 return _client.GetActorComponentNames(actor.GetId());
468 }
469
470 std::vector<std::string> GetActorBoneNames(const Actor &actor) {
471 return _client.GetActorBoneNames(actor.GetId());
472 }
473
474 std::vector<geom::Transform> GetActorSocketWorldTransforms(const Actor &actor) {
476 }
477
478 std::vector<geom::Transform> GetActorSocketRelativeTransforms(const Actor &actor) {
480 }
481
482 std::vector<std::string> GetActorSocketNames(const Actor &actor) {
483 return _client.GetActorSocketNames(actor.GetId());
484 }
485
486 void SetActorLocation(Actor &actor, const geom::Location &location) {
487 _client.SetActorLocation(actor.GetId(), location);
488 }
489
490 void SetActorTransform(Actor &actor, const geom::Transform &transform) {
491 _client.SetActorTransform(actor.GetId(), transform);
492 }
493
494 void SetActorSimulatePhysics(Actor &actor, bool enabled) {
495 _client.SetActorSimulatePhysics(actor.GetId(), enabled);
496 }
497
498 void SetActorCollisions(Actor &actor, bool enabled) {
499 _client.SetActorCollisions(actor.GetId(), enabled);
500 }
501
502 void SetActorCollisions(ActorId actor_id, bool enabled) {
503 _client.SetActorCollisions(actor_id, enabled);
504 }
505
506 void SetActorDead(Actor &actor) {
507 _client.SetActorDead(actor.GetId());
508 }
509
510 void SetActorDead(ActorId actor_id) {
511 _client.SetActorDead(actor_id);
512 }
513
514 void SetActorEnableGravity(Actor &actor, bool enabled) {
515 _client.SetActorEnableGravity(actor.GetId(), enabled);
516 }
517
518 /// @}
519 // =========================================================================
520 /// @name Operations with vehicles
521 // =========================================================================
522 /// @{
523
524 void SetVehicleAutopilot(Vehicle &vehicle, bool enabled = true) {
525 _client.SetActorAutopilot(vehicle.GetId(), enabled);
526 }
527
531
532 void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled = true) {
533 _client.ShowVehicleDebugTelemetry(vehicle.GetId(), enabled);
534 }
535
536 void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
537 _client.ApplyControlToVehicle(vehicle.GetId(), control);
538 }
539
540 void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
541 _client.ApplyControlToVehicle(vehicle.GetId(), control);
542 }
543
547
551
555
556 void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control) {
557 _client.ApplyControlToWalker(walker.GetId(), control);
558 }
559
563
565 return _client.SetBonesTransform(walker.GetId(), bones);
566 }
567
568 void BlendPose(Walker &walker, float blend) {
569 return _client.BlendPose(walker.GetId(), blend);
570 }
571
573 return _client.GetPoseFromAnimation(walker.GetId());
574 }
575
577 _client.ApplyPhysicsControlToVehicle(vehicle.GetId(), physicsControl);
578 }
579
580 void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state) {
581 _client.SetLightStateToVehicle(vehicle.GetId(), light_state);
582 }
583
584 void OpenVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx) {
585 _client.OpenVehicleDoor(vehicle.GetId(), door_idx);
586 }
587
588 void CloseVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx) {
589 _client.CloseVehicleDoor(vehicle.GetId(), door_idx);
590 }
591
592 void SetWheelSteerDirection(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location, float angle_in_deg) {
593 _client.SetWheelSteerDirection(vehicle.GetId(), wheel_location, angle_in_deg);
594 }
595
596 float GetWheelSteerAngle(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location) {
597 return _client.GetWheelSteerAngle(vehicle.GetId(), wheel_location);
598 }
599
600 void EnableCarSim(Vehicle &vehicle, std::string simfile_path) {
601 _client.EnableCarSim(vehicle.GetId(), simfile_path);
602 }
603
604 void UseCarSimRoad(Vehicle &vehicle, bool enabled) {
605 _client.UseCarSimRoad(vehicle.GetId(), enabled);
606 }
607
609 uint64_t MaxSubsteps,
610 float MaxSubstepDeltaTime,
611 std::string VehicleJSON,
612 std::string PowertrainJSON,
613 std::string TireJSON,
614 std::string BaseJSONPath) {
616 MaxSubsteps,
617 MaxSubstepDeltaTime,
618 VehicleJSON,
619 PowertrainJSON,
620 TireJSON,
621 BaseJSONPath);
622 }
623
626 }
627
628 /// @}
629 // =========================================================================
630 /// @name Operations with the recorder
631 // =========================================================================
632 /// @{
633
634 std::string StartRecorder(std::string name, bool additional_data) {
635 return _client.StartRecorder(std::move(name), additional_data);
636 }
637
638 void StopRecorder(void) {
640 }
641
642 std::string ShowRecorderFileInfo(std::string name, bool show_all) {
643 return _client.ShowRecorderFileInfo(std::move(name), show_all);
644 }
645
646 std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
647 return _client.ShowRecorderCollisions(std::move(name), type1, type2);
648 }
649
650 std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
651 return _client.ShowRecorderActorsBlocked(std::move(name), min_time, min_distance);
652 }
653
654 std::string ReplayFile(std::string name, double start, double duration,
655 uint32_t follow_id, bool replay_sensors) {
656 return _client.ReplayFile(std::move(name), start, duration, follow_id, replay_sensors);
657 }
658
659 void SetReplayerTimeFactor(double time_factor) {
660 _client.SetReplayerTimeFactor(time_factor);
661 }
662
663 void SetReplayerIgnoreHero(bool ignore_hero) {
664 _client.SetReplayerIgnoreHero(ignore_hero);
665 }
666
667 void SetReplayerIgnoreSpectator(bool ignore_spectator) {
668 _client.SetReplayerIgnoreSpectator(ignore_spectator);
669 }
670
671 void StopReplayer(bool keep_actors) {
672 _client.StopReplayer(keep_actors);
673 }
674
675 /// @}
676 // =========================================================================
677 /// @name Operations with sensors
678 // =========================================================================
679 /// @{
680
682 const Sensor &sensor,
683 std::function<void(SharedPtr<sensor::SensorData>)> callback);
684
685 void UnSubscribeFromSensor(Actor &sensor);
686
687 void EnableForROS(const Sensor &sensor);
688
689 void DisableForROS(const Sensor &sensor);
690
691 bool IsEnabledForROS(const Sensor &sensor);
692
694 Actor & sensor,
695 uint32_t gbuffer_id,
696 std::function<void(SharedPtr<sensor::SensorData>)> callback);
697
699 Actor & sensor,
700 uint32_t gbuffer_id);
701
702 void Send(const Sensor &sensor, std::string message);
703
704 /// @}
705 // =========================================================================
706 /// @name Operations with traffic lights
707 // =========================================================================
708 /// @{
709
710 void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState) {
711 _client.SetTrafficLightState(trafficLight.GetId(), trafficLightState);
712 }
713
714 void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime) {
715 _client.SetTrafficLightGreenTime(trafficLight.GetId(), greenTime);
716 }
717
718 void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime) {
719 _client.SetTrafficLightYellowTime(trafficLight.GetId(), yellowTime);
720 }
721
722 void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime) {
723 _client.SetTrafficLightRedTime(trafficLight.GetId(), redTime);
724 }
725
726 void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze) {
727 _client.FreezeTrafficLight(trafficLight.GetId(), freeze);
728 }
729
731 _client.ResetTrafficLightGroup(trafficLight.GetId());
732 }
733
737
738 std::vector<geom::BoundingBox> GetLightBoxes(const TrafficLight &trafficLight) const {
739 return _client.GetLightBoxes(trafficLight.GetId());
740 }
741
742 std::vector<ActorId> GetGroupTrafficLights(TrafficLight &trafficLight) {
743 return _client.GetGroupTrafficLights(trafficLight.GetId());
744 }
745
746 /// @}
747 // =========================================================================
748 /// @name Debug
749 // =========================================================================
750 /// @{
751
752 void DrawDebugShape(const rpc::DebugShape &shape) {
753 _client.DrawDebugShape(shape);
754 }
755
756 /// @}
757 // =========================================================================
758 /// @name Apply commands in batch
759 // =========================================================================
760 /// @{
761
762 void ApplyBatch(std::vector<rpc::Command> commands, bool do_tick_cue) {
763 _client.ApplyBatch(std::move(commands), do_tick_cue);
764 }
765
766 auto ApplyBatchSync(std::vector<rpc::Command> commands, bool do_tick_cue) {
767 return _client.ApplyBatchSync(std::move(commands), do_tick_cue);
768 }
769
770 /// @}
771 // =========================================================================
772 /// @name Operations lights
773 // =========================================================================
774 /// @{
775
779
780 std::vector<rpc::LightState> QueryLightsStateToServer() const {
782 }
783
785 std::vector<rpc::LightState>& lights,
786 bool discard_client = false) const {
787 _client.UpdateServerLightsState(lights, discard_client);
788 }
789
790 void UpdateDayNightCycle(const bool active) const {
792 }
793
794 size_t RegisterLightUpdateChangeEvent(std::function<void(WorldSnapshot)> callback) {
795 DEBUG_ASSERT(_episode != nullptr);
796 return _episode->RegisterLightUpdateChangeEvent(std::move(callback));
797 }
798
800 DEBUG_ASSERT(_episode != nullptr);
801 _episode->RemoveLightUpdateChangeEvent(id);
802 }
803
804 void FreezeAllTrafficLights(bool frozen);
805
806 /// @}
807 // =========================================================================
808 /// @name Texture updating operations
809 // =========================================================================
810 /// @{
811
813 const std::vector<std::string> &objects_name,
814 const rpc::MaterialParameter& parameter,
815 const rpc::TextureColor& Texture);
816
818 const std::vector<std::string> &objects_name,
819 const rpc::MaterialParameter& parameter,
820 const rpc::TextureFloatColor& Texture);
821
822 std::vector<std::string> GetNamesOfAllObjects() const;
823
824 /// @}
825
826 private:
827
828 bool ShouldUpdateMap(rpc::MapInfo& map_info);
829
831
833
834 std::shared_ptr<Episode> _episode;
835
837
839
840 std::string _open_drive_file;
841 };
842
843} // namespace detail
844} // namespace client
845} // namespace carla
#define DEBUG_ASSERT(predicate)
Definition Debug.h:66
#define RELEASE_ASSERT(pred)
Definition Debug.h:84
Inherit (privately) to suppress copy/move construction and assignment.
Contains all the necessary information for spawning an Actor.
Represents an actor in the simulation.
static SharedPtr< Actor > MakeActor(EpisodeProxy episode, rpc::Actor actor_description, GarbageCollectionPolicy garbage_collection_policy)
Create an Actor based on the provided actor_description.
Provides communication with the rpc and streaming servers of a CARLA simulator.
void SetReplayerIgnoreHero(bool ignore_hero)
geom::Transform GetActorComponentRelativeTransform(rpc::ActorId actor, const std::string componentName)
void SetTrafficLightRedTime(rpc::ActorId traffic_light, float red_time)
void ApplyControlToWalker(rpc::ActorId walker, const rpc::WalkerControl &control)
void OpenVehicleDoor(rpc::ActorId vehicle, const rpc::VehicleDoor door_idx)
const std::string GetEndpoint() const
rpc::WeatherParameters GetWeatherParameters()
std::vector< std::string > GetActorBoneNames(rpc::ActorId actor)
void ApplyPhysicsControlToVehicle(rpc::ActorId vehicle, const rpc::VehiclePhysicsControl &physics_control)
void CloseVehicleDoor(rpc::ActorId vehicle, const rpc::VehicleDoor door_idx)
void LoadLevelLayer(rpc::MapLayer map_layer) const
void SetActorTargetVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
std::vector< std::string > GetAvailableMaps()
rpc::VehicleLightState GetVehicleLightState(rpc::ActorId vehicle) const
rpc::VehicleTelemetryData GetVehicleTelemetryData(rpc::ActorId vehicle) const
void DisableActorConstantVelocity(rpc::ActorId actor)
void EnableActorConstantVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
rpc::AckermannControllerSettings GetAckermannControllerSettings(rpc::ActorId vehicle) const
void EnableChronoPhysics(rpc::ActorId vehicle, uint64_t MaxSubsteps, float MaxSubstepDeltaTime, std::string VehicleJSON, std::string PowertrainJSON, std::string TireJSON, std::string BaseJSONPath)
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
std::vector< rpc::CommandResponse > ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue)
std::vector< ActorId > GetGroupTrafficLights(rpc::ActorId traffic_light)
void SetActorCollisions(rpc::ActorId actor, bool enabled)
void ApplyAckermannControllerSettings(rpc::ActorId vehicle, const rpc::AckermannControllerSettings &settings)
void SetActorAutopilot(rpc::ActorId vehicle, bool enabled)
void ResetTrafficLightGroup(rpc::ActorId traffic_light)
std::vector< std::string > GetActorComponentNames(rpc::ActorId actor)
void SetActorLocation(rpc::ActorId actor, const geom::Location &location)
void ShowVehicleDebugTelemetry(rpc::ActorId vehicle, bool enabled)
void SetTrafficLightYellowTime(rpc::ActorId traffic_light, float yellow_time)
void BlendPose(rpc::ActorId walker, float blend)
rpc::VehiclePhysicsControl GetVehiclePhysicsControl(rpc::ActorId vehicle) const
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 AddActorImpulse(rpc::ActorId actor, const geom::Vector3D &impulse)
void DrawDebugShape(const rpc::DebugShape &shape)
void SetActorTransform(rpc::ActorId actor, const geom::Transform &transform)
void SetActorDead(rpc::ActorId actor)
void ApplyBatch(std::vector< rpc::Command > commands, bool do_tick_cue)
void SetTrafficLightGreenTime(rpc::ActorId traffic_light, float green_time)
void SetWeatherParameters(const rpc::WeatherParameters &weather)
void FreezeTrafficLight(rpc::ActorId traffic_light, bool freeze)
void AddActorAngularImpulse(rpc::ActorId actor, const geom::Vector3D &vector)
std::string StartRecorder(std::string name, bool additional_data)
std::vector< geom::Transform > GetActorSocketWorldTransforms(rpc::ActorId actor)
bool DestroyActor(rpc::ActorId actor)
bool AddTrafficManagerRunning(std::pair< std::string, uint16_t > trafficManagerInfo) const
Informs the server that a Traffic Manager is running on <IP, port>
std::vector< geom::Transform > GetActorBoneWorldTransforms(rpc::ActorId actor)
bool IsTrafficManagerRunning(uint16_t port) const
Querry to know if a Traffic Manager is running on port
void SetReplayerIgnoreSpectator(bool ignore_spectator)
std::vector< geom::BoundingBox > GetLightBoxes(rpc::ActorId traffic_light) const
float GetWheelSteerAngle(rpc::ActorId vehicle, rpc::VehicleWheelLocation wheel_location)
void AddActorForce(rpc::ActorId actor, const geom::Vector3D &force)
std::string ShowRecorderCollisions(std::string name, char type1, char type2)
void SetLightStateToVehicle(rpc::ActorId vehicle, const rpc::VehicleLightState &light_state)
std::vector< geom::BoundingBox > GetLevelBBs(uint8_t queried_tag) const
Returns all the BBs of all the elements of the level
std::vector< rpc::LabelledPoint > CastRay(geom::Location start_location, geom::Location end_location) const
void EnableCarSim(rpc::ActorId vehicle, std::string simfile_path)
void SetTimeout(time_duration timeout)
geom::Transform GetActorComponentWorldTransform(rpc::ActorId actor, const std::string componentName)
std::vector< geom::Transform > GetActorBoneRelativeTransforms(rpc::ActorId actor)
void SetActorEnableGravity(rpc::ActorId actor, bool enabled)
void SetActorSimulatePhysics(rpc::ActorId actor, bool enabled)
void RestorePhysXPhysics(rpc::ActorId vehicle)
void ApplyAckermannControlToVehicle(rpc::ActorId vehicle, const rpc::VehicleAckermannControl &control)
std::string ShowRecorderFileInfo(std::string name, bool show_all)
void SetReplayerTimeFactor(double time_factor)
void SetTrafficLightState(rpc::ActorId traffic_light, const rpc::TrafficLightState trafficLightState)
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id, bool replay_sensors)
std::vector< std::string > GetActorSocketNames(rpc::ActorId actor)
rpc::WalkerBoneControlOut GetBonesTransform(rpc::ActorId walker)
void UnloadLevelLayer(rpc::MapLayer map_layer) const
void SetWheelSteerDirection(rpc::ActorId vehicle, rpc::VehicleWheelLocation vehicle_wheel, float angle_in_deg)
void SetBonesTransform(rpc::ActorId walker, const rpc::WalkerBoneControlIn &bones)
void SetActorTargetAngularVelocity(rpc::ActorId actor, const geom::Vector3D &vector)
void UseCarSimRoad(rpc::ActorId vehicle, bool enabled)
std::pair< bool, rpc::LabelledPoint > ProjectPoint(geom::Location location, geom::Vector3D direction, float search_distance) const
std::vector< rpc::EnvironmentObject > GetEnvironmentObjects(uint8_t queried_tag) const
void UpdateServerLightsState(std::vector< rpc::LightState > &lights, bool discard_client=false) const
std::vector< geom::Transform > GetActorSocketRelativeTransforms(rpc::ActorId actor)
std::vector< rpc::LightState > QueryLightsStateToServer() const
void GetPoseFromAnimation(rpc::ActorId walker)
void DestroyTrafficManager(uint16_t port) const
void ApplyControlToVehicle(rpc::ActorId vehicle, const rpc::VehicleControl &control)
void UpdateDayNightCycle(const bool active) const
void EnableEnvironmentObjects(std::vector< uint64_t > env_objects_ids, bool enable) const
rpc::EpisodeSettings GetEpisodeSettings()
void SetIMUISensorGravity(float NewIMUISensorGravity)
Connects and controls a CARLA Simulator.
Definition Simulator.h:52
WorldSnapshot WaitForTick(time_duration timeout)
rpc::WalkerBoneControlOut GetBonesTransform(Walker &walker)
Definition Simulator.h:560
void SetActorCollisions(Actor &actor, bool enabled)
Definition Simulator.h:498
float GetWheelSteerAngle(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location)
Definition Simulator.h:596
std::shared_ptr< Episode > _episode
Definition Simulator.h:834
void SetActorTargetAngularVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition Simulator.h:411
void CloseVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx)
Definition Simulator.h:588
rpc::ActorState GetActorState(const Actor &actor) const
Definition Simulator.h:387
rpc::VehicleLightState GetVehicleLightState(const Vehicle &vehicle) const
Definition Simulator.h:274
std::vector< rpc::Actor > GetAllTheActorsInTheEpisode() const
Definition Simulator.h:339
void AddActorAngularImpulse(const Actor &actor, const geom::Vector3D &vector)
Definition Simulator.h:438
void DestroyTrafficManager(uint16_t port) const
Definition Simulator.h:232
bool ShouldUpdateMap(rpc::MapInfo &map_info)
void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control)
Definition Simulator.h:556
void AddPendingException(std::string e)
Definition Simulator.h:236
void DisableForROS(const Sensor &sensor)
void SetVehicleAutopilot(Vehicle &vehicle, bool enabled=true)
Definition Simulator.h:524
std::vector< geom::Transform > GetActorSocketRelativeTransforms(const Actor &actor)
Definition Simulator.h:478
void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState)
Definition Simulator.h:710
geom::Transform GetActorComponentWorldTransform(const Actor &actor, const std::string componentName)
Definition Simulator.h:450
void AddActorTorque(const Actor &actor, const geom::Vector3D &torque)
Definition Simulator.h:442
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id, bool replay_sensors)
Definition Simulator.h:654
std::vector< rpc::EnvironmentObject > GetEnvironmentObjects(uint8_t queried_tag) const
Definition Simulator.h:283
void RequestFile(const std::string &name) const
std::vector< geom::BoundingBox > GetLevelBBs(uint8_t queried_tag) const
Returns all the BBs of all the elements of the level
Definition Simulator.h:279
void EnableChronoPhysics(Vehicle &vehicle, uint64_t MaxSubsteps, float MaxSubstepDeltaTime, std::string VehicleJSON, std::string PowertrainJSON, std::string TireJSON, std::string BaseJSONPath)
Definition Simulator.h:608
void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime)
Definition Simulator.h:718
void UseCarSimRoad(Vehicle &vehicle, bool enabled)
Definition Simulator.h:604
std::string StartRecorder(std::string name, bool additional_data)
Definition Simulator.h:634
time_duration GetNetworkingTimeout()
Definition Simulator.h:174
rpc::WeatherParameters GetWeatherParameters()
Definition Simulator.h:254
std::vector< geom::Transform > GetActorBoneRelativeTransforms(const Actor &actor)
Definition Simulator.h:462
void ApplyPhysicsControlToVehicle(Vehicle &vehicle, const rpc::VehiclePhysicsControl &physicsControl)
Definition Simulator.h:576
std::vector< std::string > GetActorSocketNames(const Actor &actor)
Definition Simulator.h:482
void OpenVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx)
Definition Simulator.h:584
void UnloadLevelLayer(rpc::MapLayer map_layers) const
Definition Simulator.h:82
geom::Location GetActorLocation(const Actor &actor) const
Definition Simulator.h:391
void SetActorTransform(Actor &actor, const geom::Transform &transform)
Definition Simulator.h:490
void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition Simulator.h:414
EpisodeProxy ReloadEpisode(bool reset_settings=true)
Definition Simulator.h:72
void EnableForROS(const Sensor &sensor)
geom::Transform GetActorTransform(const Actor &actor) const
Definition Simulator.h:395
boost::optional< rpc::Actor > GetActorById(ActorId id) const
Definition Simulator.h:329
void LoadLevelLayer(rpc::MapLayer map_layers) const
Definition Simulator.h:78
void RegisterAIController(const WalkerAIController &controller)
void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition Simulator.h:540
void SetIMUISensorGravity(float NewIMUISensorGravity)
Definition Simulator.h:266
void ApplyBatch(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition Simulator.h:762
SharedPtr< LightManager > _light_manager
Definition Simulator.h:832
void RemoveOnTickEvent(size_t id)
Definition Simulator.h:199
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
void ApplyAckermannControllerSettings(Vehicle &vehicle, const rpc::AckermannControllerSettings &settings)
Definition Simulator.h:552
SharedPtr< Actor > MakeActor(rpc::Actor actor_description, GarbageCollectionPolicy gc=GarbageCollectionPolicy::Disabled)
Creates an actor instance out of a description of an existing actor.
Definition Simulator.h:350
void UpdateDayNightCycle(const bool active) const
Definition Simulator.h:790
bool IsEnabledForROS(const Sensor &sensor)
void SetBonesTransform(Walker &walker, const rpc::WalkerBoneControlIn &bones)
Definition Simulator.h:564
size_t RegisterOnTickEvent(std::function< void(WorldSnapshot)> callback)
Definition Simulator.h:194
SharedPtr< BlueprintLibrary > GetBlueprintLibrary()
void UpdateServerLightsState(std::vector< rpc::LightState > &lights, bool discard_client=false) const
Definition Simulator.h:784
std::vector< std::string > GetActorBoneNames(const Actor &actor)
Definition Simulator.h:470
std::vector< geom::Transform > GetActorBoneWorldTransforms(const Actor &actor)
Definition Simulator.h:458
Simulator(const std::string &host, uint16_t port, size_t worker_threads=0u, bool enable_garbage_collection=false)
Definition Simulator.cpp:72
void EnableEnvironmentObjects(std::vector< uint64_t > env_objects_ids, bool enable) const
Definition Simulator.h:287
const GarbageCollectionPolicy _gc_policy
Definition Simulator.h:836
void SetActorSimulatePhysics(Actor &actor, bool enabled)
Definition Simulator.h:494
std::vector< std::string > GetAvailableMaps()
Definition Simulator.h:136
void SetActorEnableGravity(Actor &actor, bool enabled)
Definition Simulator.h:514
void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition Simulator.h:536
void SetWeatherParameters(const rpc::WeatherParameters &weather)
Definition Simulator.h:258
rpc::VehicleLightStateList GetVehiclesLightStates()
Returns a list of pairs where the firts element is the vehicle ID and the second one is the light sta...
bool DestroyActor(ActorId actor_id)
Definition Simulator.h:373
void UnSubscribeFromGBuffer(Actor &sensor, uint32_t gbuffer_id)
void SubscribeToSensor(const Sensor &sensor, std::function< void(SharedPtr< sensor::SensorData >)> callback)
void GetPoseFromAnimation(Walker &walker)
Definition Simulator.h:572
std::string ShowRecorderCollisions(std::string name, char type1, char type2)
Definition Simulator.h:646
auto ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition Simulator.h:766
void UnregisterAIController(const WalkerAIController &controller)
void BlendPose(Walker &walker, float blend)
Definition Simulator.h:568
void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state)
Definition Simulator.h:580
void SetActorDead(Actor &actor)
Definition Simulator.h:506
void ResetTrafficLightGroup(TrafficLight &trafficLight)
Definition Simulator.h:730
void SetReplayerIgnoreHero(bool ignore_hero)
Definition Simulator.h:663
std::vector< uint8_t > GetCacheFile(const std::string &name, const bool request_otherwise) const
void ApplyColorTextureToObjects(const std::vector< std::string > &objects_name, const rpc::MaterialParameter &parameter, const rpc::TextureColor &Texture)
– Texture updating operations
void DrawDebugShape(const rpc::DebugShape &shape)
Definition Simulator.h:752
std::vector< std::string > GetActorComponentNames(const Actor &actor)
Definition Simulator.h:466
std::shared_ptr< WalkerNavigation > GetNavigation()
geom::Vector3D GetActorAcceleration(const Actor &actor) const
Definition Simulator.h:446
bool SetFilesBaseFolder(const std::string &path)
SharedPtr< Actor > GetSpectator()
std::vector< rpc::LightState > QueryLightsStateToServer() const
Definition Simulator.h:780
geom::Vector3D GetActorVelocity(const Actor &actor) const
Definition Simulator.h:399
EpisodeProxy LoadOpenDriveEpisode(std::string opendrive, const rpc::OpendriveGenerationParameters &params, bool reset_settings=true)
void SetPedestriansCrossFactor(float percentage)
void FreezeAllTrafficLights(bool frozen)
rpc::VehicleTelemetryData GetVehicleTelemetryData(const Vehicle &vehicle) const
Definition Simulator.h:528
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)
void EnableCarSim(Vehicle &vehicle, std::string simfile_path)
Definition Simulator.h:600
size_t RegisterLightUpdateChangeEvent(std::function< void(WorldSnapshot)> callback)
Definition Simulator.h:794
bool IsTrafficManagerRunning(uint16_t port) const
Query to know if a Traffic Manager is running on port
Definition Simulator.h:217
void SetWheelSteerDirection(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location, float angle_in_deg)
Definition Simulator.h:592
void SetNetworkingTimeout(time_duration timeout)
Definition Simulator.h:170
void SetActorLocation(Actor &actor, const geom::Location &location)
Definition Simulator.h:486
SharedPtr< LightManager > GetLightManager() const
Definition Simulator.h:776
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
std::vector< rpc::Actor > GetActorsById(const std::vector< ActorId > &actor_ids) const
Definition Simulator.h:334
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
Definition Simulator.h:650
void UnSubscribeFromSensor(Actor &sensor)
EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layers=rpc::MapLayer::All)
Definition Simulator.cpp:87
rpc::AckermannControllerSettings GetAckermannControllerSettings(const Vehicle &vehicle) const
Definition Simulator.h:548
void ApplyAckermannControlToVehicle(Vehicle &vehicle, const rpc::VehicleAckermannControl &control)
Definition Simulator.h:544
void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime)
Definition Simulator.h:722
void RemoveLightUpdateChangeEvent(size_t id)
Definition Simulator.h:799
void RestorePhysXPhysics(Vehicle &vehicle)
Definition Simulator.h:624
WorldSnapshot GetWorldSnapshot() const
Definition Simulator.h:123
void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze)
Definition Simulator.h:726
uint64_t Tick(time_duration timeout)
void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector)
Definition Simulator.h:403
std::vector< rpc::LabelledPoint > CastRay(geom::Location start_location, geom::Location end_location) const
Definition Simulator.h:298
void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse)
Definition Simulator.h:422
void AddActorForce(const Actor &actor, const geom::Vector3D &force, const geom::Vector3D &location)
Definition Simulator.h:434
void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location)
Definition Simulator.h:426
void SubscribeToGBuffer(Actor &sensor, uint32_t gbuffer_id, std::function< void(SharedPtr< sensor::SensorData >)> callback)
void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime)
Definition Simulator.h:714
ActorSnapshot GetActorSnapshot(ActorId actor_id) const
Definition Simulator.h:378
void StopReplayer(bool keep_actors)
Definition Simulator.h:671
void AddActorForce(const Actor &actor, const geom::Vector3D &force)
Definition Simulator.h:430
geom::Vector3D GetActorAngularVelocity(const Actor &actor) const
Definition Simulator.h:407
std::pair< bool, rpc::LabelledPoint > ProjectPoint(geom::Location location, geom::Vector3D direction, float search_distance) const
Definition Simulator.h:293
GarbageCollectionPolicy GetGarbageCollectionPolicy() const
Definition Simulator.h:160
void SetActorCollisions(ActorId actor_id, bool enabled)
Definition Simulator.h:502
std::vector< std::string > GetNamesOfAllObjects() const
void SetReplayerTimeFactor(double time_factor)
Definition Simulator.h:659
SharedPtr< Map > GetCurrentMap()
bool AddTrafficManagerRunning(std::pair< std::string, uint16_t > trafficManagerInfo) const
Informs that a Traffic Manager is running on <IP, port>
Definition Simulator.h:228
geom::Transform GetActorComponentRelativeTransform(const Actor &actor, std::string componentName)
Definition Simulator.h:454
rpc::VehiclePhysicsControl GetVehiclePhysicsControl(const Vehicle &vehicle) const
Definition Simulator.h:270
void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled=true)
Definition Simulator.h:532
rpc::EpisodeSettings GetEpisodeSettings()
Definition Simulator.h:248
ActorSnapshot GetActorSnapshot(const Actor &actor) const
Definition Simulator.h:383
bool DestroyActor(Actor &actor)
std::vector< geom::Transform > GetActorSocketWorldTransforms(const Actor &actor)
Definition Simulator.h:474
void SetPedestriansSeed(unsigned int seed)
void DisableActorConstantVelocity(const Actor &actor)
Definition Simulator.h:418
std::vector< geom::BoundingBox > GetLightBoxes(const TrafficLight &trafficLight) const
Definition Simulator.h:738
boost::optional< geom::Location > GetRandomLocationFromNavigation()
void Send(const Sensor &sensor, std::string message)
void SetActorDead(ActorId actor_id)
Definition Simulator.h:510
std::string ShowRecorderFileInfo(std::string name, bool show_all)
Definition Simulator.h:642
std::vector< ActorId > GetGroupTrafficLights(TrafficLight &trafficLight)
Definition Simulator.h:742
void SetReplayerIgnoreSpectator(bool ignore_spectator)
Definition Simulator.h:667
Defines the physical appearance of a vehicle whitch is obtained by the sensors.
Positive time duration up to milliseconds resolution.
Definition Time.h:19
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
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
Seting for map generation from opendrive without additional geometry