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 /// 连接并控制 CARLA 模拟器。
50 : public std::enable_shared_from_this<Simulator>,
52 private NonCopyable {
53 public:
54
55 // =========================================================================
56 /// @name 构造函数
57 // =========================================================================
58 /// @{
59
60 explicit Simulator(
61 const std::string &host, // 主服务器的IP地址
62 uint16_t port, // 连接主服务器的端口号,默认为 2000
63 size_t worker_threads = 0u, // 仿真器使用的工作线程数,默认全部启用
64 bool enable_garbage_collection = false); // 是否启用垃圾回收,默认不启用
65
66 /// @}
67 // =========================================================================
68 /// @name 加载新的场景
69 // =========================================================================
70 /// @{
71
72 EpisodeProxy ReloadEpisode(bool reset_settings = true) {
73 return LoadEpisode("", reset_settings);
74 }
75
76 // 根据地图名和可选的重置设置以及地图层来加载一个场景
77 EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings = true, rpc::MapLayer map_layers = rpc::MapLayer::All);
78 // 加载指定的地图层
79 void LoadLevelLayer(rpc::MapLayer map_layers) const {
80 _client.LoadLevelLayer(map_layers);
81 }
82 // 卸载指定的地图层
83 void UnloadLevelLayer(rpc::MapLayer map_layers) const {
84 _client.UnloadLevelLayer(map_layers);
85 }
86
87 // 根据OpenDrive文件和生成参数加载一个场景
89 std::string opendrive,
91 bool reset_settings = true);
92
93 /// @}
94 // =========================================================================
95 /// @name 访问当前场景
96 // =========================================================================
97 /// @{
98
99 /// @pre Cannot be called previous to GetCurrentEpisode.
100 // 获取当前场景的ID,确保当前场景已准备好
103 DEBUG_ASSERT(_episode != nullptr);
104 return _episode->GetId();
105 }
106 // 确保当前场景已准备好
108 // 获取当前场景的代理
110
111 /// @}
112 // =========================================================================
113 /// @name 世界快照
114 // =========================================================================
115 /// @{
116
117 // 获取当前世界(场景)的实例
119 return World{GetCurrentEpisode()};
120 }
121
122 /// @}
123 // =========================================================================
124 /// @name 世界快照
125 // =========================================================================
126 /// @{
127
128
129// 获取当前世界的快照
131 DEBUG_ASSERT(_episode != nullptr);
132 return WorldSnapshot{_episode->GetState()};
133 }
134
135 /// @}
136 // =========================================================================
137 /// @name 地图相关的方法
138 // =========================================================================
139 /// @{
140
141
142// 获取当前场景的地图实例
144
145 // 获取所有可用的地图名
146 std::vector<std::string> GetAvailableMaps() {
147 return _client.GetAvailableMaps();
148 }
149
150 /// @}
151 // =========================================================================
152 /// @name 所需文件相关的方法
153 // =========================================================================
154 /// @{
155
156// 设置文件基础文件夹
157 bool SetFilesBaseFolder(const std::string &path);
158
159 // 获取指定文件夹中所需的文件列表,可以选择是否下载
160 std::vector<std::string> GetRequiredFiles(const std::string &folder = "", const bool download = true) const;
161
162 // 请求特定文件
163 void RequestFile(const std::string &name) const;
164
165 // 从缓存中获取文件,如果缓存中没有且request_otherwise为true,则尝试请求
166 std::vector<uint8_t> GetCacheFile(const std::string &name, const bool request_otherwise) const;
167
168 /// @}
169 // =========================================================================
170 /// @name 垃圾收集策略
171 // =========================================================================
172 /// @{
173
177
178 /// @}
179 // =========================================================================
180 /// @name 纯网络操作
181 // =========================================================================
182 /// @{
183
184 // 设置网络超时时间
186 _client.SetTimeout(timeout); // 设置客户端的超时时间
187 }
188
190 return _client.GetTimeout();// 获取客户端的超时时间
191 }
192 // 获取客户端版本
193 std::string GetClientVersion() {
194 return _client.GetClientVersion();// 从客户端获取版本信息
195 }
196 // 获取服务器版本
197 std::string GetServerVersion() {
198 return _client.GetServerVersion();// 从服务器获取版本信息
199 }
200
201 /// @}
202 // =========================================================================
203 /// @name 节拍
204 // =========================================================================
205 /// @{
206
207// 等待一个节拍(模拟时间步),返回该时间步的世界快照
209 // 注册一个在每个节拍(模拟时间步)被调用的回调函数
210 size_t RegisterOnTickEvent(std::function<void(WorldSnapshot)> callback) {
211 DEBUG_ASSERT(_episode != nullptr);
212 return _episode->RegisterOnTickEvent(std::move(callback));
213 }
214 // 移除一个节拍回调
215 void RemoveOnTickEvent(size_t id) {
216 DEBUG_ASSERT(_episode != nullptr);
217 _episode->RemoveOnTickEvent(id);
218 }
219 // 执行一个节拍(模拟时间步),返回该时间步的模拟时间(通常以微秒为单位)
220 uint64_t Tick(time_duration timeout);
221
222 /// @}
223 // =========================================================================
224 /// @name 访问场景中的全局对象
225 // =========================================================================
226 /// @{
227
228 std :: string GetEndpoint() {
229 return _client.GetEndpoint();
230 }
231
232 /// 查询交通管理器是否正在端口上运行
233 bool IsTrafficManagerRunning(uint16_t port) const {
234 return _client.IsTrafficManagerRunning(port);
235 }
236
237 /// 获取一个填充了在端口上运行的交通管理器的 <IP, 端口> 对。
238 /// 如果没有正在运行的流量管理器,则该对将为 ("", 0)
239 std::pair<std::string, uint16_t> GetTrafficManagerRunning(uint16_t port) const {
241 }
242
243 /// 通知交通管理器正在 <IP, 端口> 上运行
244 bool AddTrafficManagerRunning(std::pair<std::string, uint16_t> trafficManagerInfo) const {
245 return _client.AddTrafficManagerRunning(trafficManagerInfo);
246 }
247
248 // 根据端口销毁交通管理器
249 void DestroyTrafficManager(uint16_t port) const {
251 }
252
253 void AddPendingException(std::string e) {
254 // 调用当前章节对象的AddPendingException方法,传入异常字符串e
255 _episode->AddPendingException(e);
256 }
257
258 // 获取蓝图库的共享指针
260
261 /// 返回一个列表,其中第一个元素是车辆 ID,第二个元素是灯光状态
263
264 // 获取当前观察者(Spectator)对象的共享指针
266
270
271 uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings);
272
276
277 // 设置新的天气参数
279 // 调用客户端的SetWeatherParameters方法,传入新的天气参数
281 }
282
283 // 获取IMU传感器的重力值
284 float GetIMUISensorGravity() const {
285 // 调用客户端的GetIMUISensorGravity方法,返回IMU传感器的重力值
287 }
288
289 // 设置IMU传感器的重力值
290 void SetIMUISensorGravity(float NewIMUISensorGravity) {
291 _client.SetIMUISensorGravity(NewIMUISensorGravity);
292 }
293
294 // 获取指定车辆的物理控制状态
296 // 调用客户端的GetVehiclePhysicsControl方法,传入车辆的ID,返回车辆的物理控制状态
297 return _client.GetVehiclePhysicsControl(vehicle.GetId());
298 }
299 // 获取指定车辆的灯光状态
301 return _client.GetVehicleLightState(vehicle.GetId());
302 }
303
304 /// Returns all the BBs of all the elements of the level
305 std::vector<geom::BoundingBox> GetLevelBBs(uint8_t queried_tag) const {
306 return _client.GetLevelBBs(queried_tag);
307 }
308 // 获取具有指定标签的环境对象
309 std::vector<rpc::EnvironmentObject> GetEnvironmentObjects(uint8_t queried_tag) const {
310 return _client.GetEnvironmentObjects(queried_tag);
311 }
312
313 // 启用或禁用具有指定ID的环境对象
315 std::vector<uint64_t> env_objects_ids,
316 bool enable) const {
317 // 调用客户端的EnableEnvironmentObjects方法,传入环境对象的ID列表和启用状态
318 _client.EnableEnvironmentObjects(env_objects_ids, enable);
319 }
320 // 投影一个点,并返回该点在地图上的标记点和是否成功投影
321 std::pair<bool,rpc::LabelledPoint> ProjectPoint(
322 geom::Location location, geom::Vector3D direction, float search_distance) const {
323 // 调用客户端的ProjectPoint方法,传入起始位置、方向和搜索距离,返回是否成功投影和标记点
324 return _client.ProjectPoint(location, direction, search_distance);
325 }
326
327 // 从一个起始位置到结束位置投射一条光线,并返回所有碰撞点
328 std::vector<rpc::LabelledPoint> CastRay(
329 geom::Location start_location, geom::Location end_location) const {
330 // 调用客户端的CastRay方法,传入起始位置和结束位置,返回光线碰撞的所有标记点列表
331 return _client.CastRay(start_location, end_location);
332 }
333
334 /// @}
335 // =========================================================================
336 /// @name 人工智能
337 // =========================================================================
338 /// @{
339 // 获取当前导航对象
340 std::shared_ptr<WalkerNavigation> GetNavigation();
341 // 通过调用此函数来更新导航状态,可能是为了处理路径计算、目标点的选择等
342 void NavigationTick();
343 // 注册AI控制器,可能是某个虚拟角色或物体的AI控制器
344 void RegisterAIController(const WalkerAIController &controller);
345 // 注销AI控制器,移除控制器与特定角色或物体的关联
346 void UnregisterAIController(const WalkerAIController &controller);
347 // 从导航对象中获取一个随机位置,这可能用于生成随机目标或逃逸点
348 boost::optional<geom::Location> GetRandomLocationFromNavigation();
349 // 设置行人交叉因素的百分比,可能影响路径规划或碰撞处理
350 void SetPedestriansCrossFactor(float percentage);
351 // 设置行人行为的随机种子,可能影响行人生成或路径选择的随机性
352 void SetPedestriansSeed(unsigned int seed);
353
354 /// @}
355 // =========================================================================
356 /// @name 参与者的一般操作
357 // =========================================================================
358 /// @{
359
360 //根据参与者的ID获取对应的演员信息
361 boost::optional<rpc::Actor> GetActorById(ActorId id) const {
362 DEBUG_ASSERT(_episode != nullptr);
363 return _episode->GetActorById(id);
364 }
365 /// 根据一组演员ID获取对应的演员信息
366 std::vector<rpc::Actor> GetActorsById(const std::vector<ActorId> &actor_ids) const {
367 DEBUG_ASSERT(_episode != nullptr);
368 return _episode->GetActorsById(actor_ids);
369 }
370 /// 获取当前 episode 中所有的演员信息
371 std::vector<rpc::Actor> GetAllTheActorsInTheEpisode() const {
372 DEBUG_ASSERT(_episode != nullptr);
373 return _episode->GetActors();
374 }
375
376 /// 根据现有参与者的描述创建一个参与者实例。请注意,这不会生成参与者。
377 ///
378 /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
379 /// returned is provided with a custom deleter that calls Destroy() on the
380 /// actor. This method does not support GarbageCollectionPolicy::Inherit.
387
388 /// 在模拟中生成一个参与者
389 ///
390 /// If @a gc is GarbageCollectionPolicy::Enabled, the shared pointer
391 /// returned is provided with a custom deleter that calls Destroy() on the
392 /// actor. If @gc is GarbageCollectionPolicy::Inherit, the default garbage
393 /// collection policy is used.
395 const ActorBlueprint &blueprint,
396 const geom::Transform &transform,
397 Actor *parent = nullptr,
400 const std::string& socket_name = "");
401 /// 销毁指定的演员
402 bool DestroyActor(Actor &actor);
403 // 根据演员ID销毁指定的演员
404 bool DestroyActor(ActorId actor_id)
405 {
406 return _client.DestroyActor(actor_id);
407 }
408 // 获取指定ID演员的快照信息
410 DEBUG_ASSERT(_episode != nullptr);
411 return _episode->GetState()->GetActorSnapshot(actor_id);
412 }
413 // 获取指定演员的快照信息
415 return GetActorSnapshot(actor.GetId());
416 }
417 // 获取指定演员的状态信息
418 rpc::ActorState GetActorState(const Actor &actor) const {
419 return GetActorSnapshot(actor).actor_state;
420 }
421 // 获取指定演员的位置
423 return GetActorSnapshot(actor).transform.location;
424 }
425 /// 获取指定演员的变换信息(包括位置、旋转、缩放)
427 return GetActorSnapshot(actor).transform;
428 }
429
430 /// 获取指定演员的速度(可能包括线性速度和角速度)
432 return GetActorSnapshot(actor).velocity;
433 }
434 /// 设置指定演员的目标速度
435 void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector) {
436 _client.SetActorTargetVelocity(actor.GetId(), vector);
437 }
438 /// 获取指定演员的角速度
441 }
442 /// 设置指定演员的目标角速度
443 void SetActorTargetAngularVelocity(const Actor &actor, const geom::Vector3D &vector) {
445 }
446 /// 启用演员的恒定速度(用于模拟持续的线性运动)
447 void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector) {
449 }
450 /// 禁用演员的恒定速度
454 /// 给指定演员施加脉冲力
455 void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse) {
456 _client.AddActorImpulse(actor.GetId(), impulse);
457 }
458
459 /// 给指定演员在特定位置施加脉冲力
460 void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location) {
461 _client.AddActorImpulse(actor.GetId(), impulse, location);
462 }
463 /// 给指定演员施加持续的力
464 void AddActorForce(const Actor &actor, const geom::Vector3D &force) {
465 _client.AddActorForce(actor.GetId(), force);
466 }
467 /// 给指定演员在特定位置施加持续的力
468 void AddActorForce(const Actor &actor, const geom::Vector3D &force, const geom::Vector3D &location) {
469 _client.AddActorForce(actor.GetId(), force, location);
470 }
471 /// 给指定演员施加角脉冲(影响角度运动)
472 void AddActorAngularImpulse(const Actor &actor, const geom::Vector3D &vector) {
473 _client.AddActorAngularImpulse(actor.GetId(), vector);
474 }
475 /// 给指定演员施加扭矩
476 void AddActorTorque(const Actor &actor, const geom::Vector3D &torque) {
477 _client.AddActorAngularImpulse(actor.GetId(), torque);
478 }
479 /// 获取指定演员的加速度
481 return GetActorSnapshot(actor).acceleration;
482 }
483 /// 获取指定演员组件的世界坐标变换信息
484 geom::Transform GetActorComponentWorldTransform(const Actor &actor, const std::string componentName) {
485 return _client.GetActorComponentWorldTransform(actor.GetId(), componentName);
486 }
487 /// 获取指定演员组件的相对坐标变换信息
488 geom::Transform GetActorComponentRelativeTransform(const Actor &actor, std::string componentName) {
489 return _client.GetActorComponentRelativeTransform(actor.GetId(), componentName);
490 }
491 // 获取Actor所有骨骼的世界变换(位置、旋转、缩放等)
492 std::vector<geom::Transform> GetActorBoneWorldTransforms(const Actor &actor) {
494 }
495 // 获取Actor所有骨骼的相对变换(相对于父对象的位置、旋转、缩放)
496 std::vector<geom::Transform> GetActorBoneRelativeTransforms(const Actor &actor) {
498 }
499 // 获取Actor的所有组件名称
500 std::vector<std::string> GetActorComponentNames(const Actor &actor) {
501 return _client.GetActorComponentNames(actor.GetId());
502 }
503 // 获取Actor的所有骨骼名称
504 std::vector<std::string> GetActorBoneNames(const Actor &actor) {
505 return _client.GetActorBoneNames(actor.GetId());
506 }
507 // 获取Actor所有插座的世界变换
508 std::vector<geom::Transform> GetActorSocketWorldTransforms(const Actor &actor) {
510 }
511 // 获取Actor所有插座的相对变换
512 std::vector<geom::Transform> GetActorSocketRelativeTransforms(const Actor &actor) {
514 }
515 // 获取Actor的所有插座名称
516 std::vector<std::string> GetActorSocketNames(const Actor &actor) {
517 return _client.GetActorSocketNames(actor.GetId());
518 }
519 ///设置 Actor 状态
520 // 设置Actor的位置
521 void SetActorLocation(Actor &actor, const geom::Location &location) {
522 _client.SetActorLocation(actor.GetId(), location);
523 }
524 // 设置Actor的变换(包括位置、旋转、缩放)
525 void SetActorTransform(Actor &actor, const geom::Transform &transform) {
526 _client.SetActorTransform(actor.GetId(), transform);
527 }
528 // 设置Actor是否启用物理仿真
529 void SetActorSimulatePhysics(Actor &actor, bool enabled) {
530 _client.SetActorSimulatePhysics(actor.GetId(), enabled);
531 }
532 // 设置Actor是否启用碰撞
533 void SetActorCollisions(Actor &actor, bool enabled) {
534 _client.SetActorCollisions(actor.GetId(), enabled);
535 }
536
537 void SetActorCollisions(ActorId actor_id, bool enabled) {
538 _client.SetActorCollisions(actor_id, enabled);
539 }
540 // 设置Actor是否死亡
541 void SetActorDead(Actor &actor) {
542 _client.SetActorDead(actor.GetId());
543 }
544
545 void SetActorDead(ActorId actor_id) {
546 _client.SetActorDead(actor_id);
547 }
548 // 设置Actor是否启用重力
549 void SetActorEnableGravity(Actor &actor, bool enabled) {
550 _client.SetActorEnableGravity(actor.GetId(), enabled);
551 }
552
553 /// @}
554 // =========================================================================
555 /// @name 车辆的操作
556 // =========================================================================
557 /// @{
558
559 // 设置车辆是否启用自动驾驶
560 void SetVehicleAutopilot(Vehicle &vehicle, bool enabled = true) {
561 _client.SetActorAutopilot(vehicle.GetId(), enabled);
562 }
563 // 获取车辆的遥测数据
567 // 显示或隐藏车辆的调试遥测数据
568 void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled = true) {
569 _client.ShowVehicleDebugTelemetry(vehicle.GetId(), enabled);
570 }
571 // 给车辆应用控制指令(如开关灯等)
572 void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
573 _client.ApplyControlToVehicle(vehicle.GetId(), control);
574 }
575 // 应用控制到车辆(例如转向、加速等)
576 void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control) {
577 _client.ApplyControlToVehicle(vehicle.GetId(), control);
578 }
579 // 应用Ackermann控制(用于像汽车这类车辆)
583
587 //Walker 操作
591 // 给Walker应用控制指令(如行走、跳跃等)
592 void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control) {
593 _client.ApplyControlToWalker(walker.GetId(), control);
594 }
595 // 获取Walker的骨骼变换
599 // 设置Walker的骨骼变换
601 return _client.SetBonesTransform(walker.GetId(), bones);
602 }
603 // 混合Walker的姿势(动画过渡)
604 void BlendPose(Walker &walker, float blend) {
605 return _client.BlendPose(walker.GetId(), blend);
606 }
607 // 从动画中获取Walker的姿势
609 return _client.GetPoseFromAnimation(walker.GetId());
610 }
611 // 应用物理控制到指定车辆
613 _client.ApplyPhysicsControlToVehicle(vehicle.GetId(), physicsControl);
614 }
615 // 设置指定车辆的灯光状态
616 void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state) {
617 _client.SetLightStateToVehicle(vehicle.GetId(), light_state);
618 }
619 // 打开指定车辆的某个车门
620 void OpenVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx) {
621 _client.OpenVehicleDoor(vehicle.GetId(), door_idx);
622 }
623 // 关闭指定车辆的某个车门
624 void CloseVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx) {
625 _client.CloseVehicleDoor(vehicle.GetId(), door_idx);
626 }
627 // 设置指定车辆的车轮转向角度
628 void SetWheelSteerDirection(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location, float angle_in_deg) {
629 _client.SetWheelSteerDirection(vehicle.GetId(), wheel_location, angle_in_deg);
630 }
631 // 获取指定车辆的车轮当前转向角度
632 float GetWheelSteerAngle(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location) {
633 return _client.GetWheelSteerAngle(vehicle.GetId(), wheel_location);
634 }
635 // 车辆物理仿真与车辆部件操作
636 // 启用CarSim模拟器
637 void EnableCarSim(Vehicle &vehicle, std::string simfile_path) {
638 _client.EnableCarSim(vehicle.GetId(), simfile_path);
639 }
640 // 启用或禁用CarSim道路
641 void UseCarSimRoad(Vehicle &vehicle, bool enabled) {
642 _client.UseCarSimRoad(vehicle.GetId(), enabled);
643 }
644 // 启用Chrono物理仿真
646 uint64_t MaxSubsteps,
647 float MaxSubstepDeltaTime,
648 std::string VehicleJSON,
649 std::string PowertrainJSON,
650 std::string TireJSON,
651 std::string BaseJSONPath) {
653 MaxSubsteps,
654 MaxSubstepDeltaTime,
655 VehicleJSON,
656 PowertrainJSON,
657 TireJSON,
658 BaseJSONPath);
659 }
660
663 }
664
665 /// @}
666 // =========================================================================
667 /// @name 记录器的操作
668 // =========================================================================
669 /// @{
670
671 // 启动录制器
672 std::string StartRecorder(std::string name, bool additional_data) {
673 // _client对象调用StartRecorder方法来启动录制。
674 // additional_data: 是否记录额外的数据,控制录制的详细程度。
675 // 使用std::move()转移name的所有权,提高效率。
676 return _client.StartRecorder(std::move(name), additional_data);
677 }
678 // 停止录制器
679 void StopRecorder(void) {
681 }
682 // 显示录制文件的相关信息
683 std::string ShowRecorderFileInfo(std::string name, bool show_all) {
684 // show_all: 是否显示所有信息。
685 return _client.ShowRecorderFileInfo(std::move(name), show_all);
686 }
687 // 显示录制期间的碰撞信息
688 std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
689 return _client.ShowRecorderCollisions(std::move(name), type1, type2);
690 }
691 // 显示在录制期间被阻挡的角色信息
692 std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
693 return _client.ShowRecorderActorsBlocked(std::move(name), min_time, min_distance);
694 }
695 // 回放录制的文件
696 std::string ReplayFile(std::string name, double start, double duration,
697 uint32_t follow_id, bool replay_sensors) {
698 return _client.ReplayFile(std::move(name), start, duration, follow_id, replay_sensors);
699 }
700 // 设置回放器的时间比例因子
701 void SetReplayerTimeFactor(double time_factor) {
702 // time_factor: 时间比例因子,控制回放速度。
703 _client.SetReplayerTimeFactor(time_factor);
704 }
705 // 设置回放器是否忽略英雄角色
706 void SetReplayerIgnoreHero(bool ignore_hero) {
707 _client.SetReplayerIgnoreHero(ignore_hero);
708 }
709 // 设置回放器是否忽略观众角色
710 void SetReplayerIgnoreSpectator(bool ignore_spectator) {
711 _client.SetReplayerIgnoreSpectator(ignore_spectator);
712 }
713 // 停止回放器
714 void StopReplayer(bool keep_actors) {
715 _client.StopReplayer(keep_actors);
716 }
717
718 /// @}
719 // =========================================================================
720 /// @name 传感器的操作
721 // =========================================================================
722 /// @{
723
724 // 订阅传感器数据
726 const Sensor &sensor,
727 std::function<void(SharedPtr<sensor::SensorData>)> callback);
728 // callback: 回调函数,当传感器数据更新时会被调用,传入数据指针。
729 // SharedPtr是智能指针,用于共享传感器数据的所有权,防止内存泄漏。
730
731 // 取消订阅传感器数据
732 void UnSubscribeFromSensor(Actor &sensor);
733
734 // 启用传感器以便与ROS通信
735 void EnableForROS(const Sensor &sensor);
736
737 // 禁用传感器与ROS通信
738 void DisableForROS(const Sensor &sensor);
739
740 // 检查传感器是否启用了ROS通信
741 bool IsEnabledForROS(const Sensor &sensor);
742
743 // 订阅传感器的GBuffer(图形缓冲区)数据
745 Actor & sensor,
746 uint32_t gbuffer_id,
747 std::function<void(SharedPtr<sensor::SensorData>)> callback);
748
749 // 取消订阅传感器的GBuffer数据
751 Actor & sensor,
752 uint32_t gbuffer_id);
753
754 // 向传感器发送消息
755 void Send(const Sensor &sensor, std::string message);
756
757 /// @}
758 // =========================================================================
759 /// @name 交通灯的操作
760 // =========================================================================
761 /// @{
762
763 // 设置交通灯的状态
764 void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState) {
765 _client.SetTrafficLightState(trafficLight.GetId(), trafficLightState);
766 }
767 // 设置交通灯的绿灯时间
768 void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime) {
769 _client.SetTrafficLightGreenTime(trafficLight.GetId(), greenTime);
770 }
771 // 设置交通灯的黄灯时间
772 void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime) {
773 _client.SetTrafficLightYellowTime(trafficLight.GetId(), yellowTime);
774 }
775 // 设置交通灯的红灯时间
776 void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime) {
777 _client.SetTrafficLightRedTime(trafficLight.GetId(), redTime);
778 }
779 // 冻结或解冻交通灯(使交通灯保持当前状态)
780 void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze) {
781 _client.FreezeTrafficLight(trafficLight.GetId(), freeze);
782 }
783 // 重置单个交通灯组的状态
785 _client.ResetTrafficLightGroup(trafficLight.GetId());
786 }
787 // 重置所有交通灯
791 // 获取与给定交通灯相关的所有 BoundingBox 对象(通常用于碰撞检测或可视化调试)
792 std::vector<geom::BoundingBox> GetLightBoxes(const TrafficLight &trafficLight) const {
793 return _client.GetLightBoxes(trafficLight.GetId());
794 }
795 // 获取与给定交通灯属于同一组的所有交通灯的 ID
796 std::vector<ActorId> GetGroupTrafficLights(TrafficLight &trafficLight) {
797 return _client.GetGroupTrafficLights(trafficLight.GetId());
798 }
799
800 /// @}
801 // =========================================================================
802 /// @name 调试
803 // =========================================================================
804 /// @{
805
806 void DrawDebugShape(const rpc::DebugShape &shape) {
807 // 绘制一个调试用的形状,用于调试或可视化
808 _client.DrawDebugShape(shape);
809 }
810
811 /// @}
812 // =========================================================================
813 /// @name Apply commands in batch
814 // =========================================================================
815 /// @{
816
817 void ApplyBatch(std::vector<rpc::Command> commands, bool do_tick_cue) {
818 // 将多个命令批量应用到服务端
819 _client.ApplyBatch(std::move(commands), do_tick_cue);
820 }
821 // 批量应用命令并同步等待结果
822 auto ApplyBatchSync(std::vector<rpc::Command> commands, bool do_tick_cue) {
823 // 同步执行批量命令
824 return _client.ApplyBatchSync(std::move(commands), do_tick_cue);
825 }
826
827 /// @}
828 // =========================================================================
829 /// @name 操作灯
830 // =========================================================================
831 /// @{
832
834 // 获取当前的灯光管理器
835 return _light_manager;
836 }
837
838 std::vector<rpc::LightState> QueryLightsStateToServer() const {
839 // 查询服务器上所有灯光的状态
841 // 向服务器查询当前所有灯光的状态并返回
842 }
843
844 // 更新服务器上的灯光状态
846 std::vector<rpc::LightState>& lights,
847 bool discard_client = false) const {
848 _client.UpdateServerLightsState(lights, discard_client);
849 }
850
851 // 更新昼夜循环(控制白天/黑夜的切换)
852 void UpdateDayNightCycle(const bool active) const {
854 }
855
856 // 注册一个灯光状态更新的事件回调
857 size_t RegisterLightUpdateChangeEvent(std::function<void(WorldSnapshot)> callback) {
858 DEBUG_ASSERT(_episode != nullptr);
859 return _episode->RegisterLightUpdateChangeEvent(std::move(callback));
860 }
861 // 移除一个灯光状态更新的事件回调
863 DEBUG_ASSERT(_episode != nullptr);
864 _episode->RemoveLightUpdateChangeEvent(id);
865 }
866 // 冻结或解冻所有交通灯
867 void FreezeAllTrafficLights(bool frozen);
868
869 /// @}
870 // =========================================================================
871 /// @name 纹理更新操作
872 // =========================================================================
873 /// @{
874
876 const std::vector<std::string> &objects_name,
877 const rpc::MaterialParameter& parameter,
878 const rpc::TextureColor& Texture);
879 // 将颜色纹理应用到一组对象上
880
882 const std::vector<std::string> &objects_name,
883 const rpc::MaterialParameter& parameter,
884 const rpc::TextureFloatColor& Texture);
885 // 将浮动颜色纹理应用到一组对象上
886
887 std::vector<std::string> GetNamesOfAllObjects() const;
888 // 获取所有对象的名称
889
890 /// @}
891
892 private:
893 // 判断是否需要更新地图
894 bool ShouldUpdateMap(rpc::MapInfo& map_info);
895
896 // 客户端对象,负责与服务器交互
898
899 // 灯光管理器,用于管理和操作场景中的灯光
901
902 // 任务场景的 Episode(任务执行环境)
903 std::shared_ptr<Episode> _episode;
904
905 // 垃圾回收策略
907
908 // 缓存的地图对象
910
911 // 存储打开的道路文件
912 std::string _open_drive_file;
913 };
914
915} // namespace detail
916} // namespace client
917} // namespace carla
#define DEBUG_ASSERT(predicate)
Definition Debug.h:68
#define RELEASE_ASSERT(pred)
Definition Debug.h:94
地图类的前向声明,用于在LaneInvasionSensor类中可能的引用。
这个类用于禁止拷贝和移动构造函数及赋值操作
包含生成参与者所需的所有必要信息。
表示模拟中的一个行为体(Actor)。
传感器基类,继承自Actor类。
车辆类的前向声明,用于在LaneInvasionSensor类中可能的引用。
Definition Vehicle.h:76
行人角色类,继承自Actor类。
Definition Walker.h:22
static SharedPtr< Actor > MakeActor(EpisodeProxy episode, rpc::Actor actor_description, GarbageCollectionPolicy garbage_collection_policy)
基于提供的 actor_description 创建一个参与者。episode 必须指向该参与者所在的章节(或者说区域)
提供与 CARLA 模拟器的 rpc 和流媒体服务器的通信。
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
获取一个填充了在端口上运行的交通管理器的 <IP, 端口> 的对。 如果没有正在运行的交通管理器,则该对将为 ("", 0)
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
通知正在 <IP, 端口> 上运行的交通管理器服务
std::vector< geom::Transform > GetActorBoneWorldTransforms(rpc::ActorId actor)
bool IsTrafficManagerRunning(uint16_t port) const
查询交通管理器是否正在端口上运行
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)
连接并控制 CARLA 模拟器。
Definition Simulator.h:52
WorldSnapshot WaitForTick(time_duration timeout)
rpc::WalkerBoneControlOut GetBonesTransform(Walker &walker)
Definition Simulator.h:596
void SetActorCollisions(Actor &actor, bool enabled)
Definition Simulator.h:533
float GetWheelSteerAngle(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location)
Definition Simulator.h:632
std::shared_ptr< Episode > _episode
Definition Simulator.h:903
void SetActorTargetAngularVelocity(const Actor &actor, const geom::Vector3D &vector)
设置指定演员的目标角速度
Definition Simulator.h:443
void CloseVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx)
Definition Simulator.h:624
rpc::ActorState GetActorState(const Actor &actor) const
Definition Simulator.h:418
rpc::VehicleLightState GetVehicleLightState(const Vehicle &vehicle) const
Definition Simulator.h:300
std::vector< rpc::Actor > GetAllTheActorsInTheEpisode() const
获取当前 episode 中所有的演员信息
Definition Simulator.h:371
void AddActorAngularImpulse(const Actor &actor, const geom::Vector3D &vector)
给指定演员施加角脉冲(影响角度运动)
Definition Simulator.h:472
void DestroyTrafficManager(uint16_t port) const
Definition Simulator.h:249
bool ShouldUpdateMap(rpc::MapInfo &map_info)
void ApplyControlToWalker(Walker &walker, const rpc::WalkerControl &control)
Definition Simulator.h:592
void AddPendingException(std::string e)
Definition Simulator.h:253
void DisableForROS(const Sensor &sensor)
void SetVehicleAutopilot(Vehicle &vehicle, bool enabled=true)
Definition Simulator.h:560
std::vector< geom::Transform > GetActorSocketRelativeTransforms(const Actor &actor)
Definition Simulator.h:512
void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState)
Definition Simulator.h:764
geom::Transform GetActorComponentWorldTransform(const Actor &actor, const std::string componentName)
获取指定演员组件的世界坐标变换信息
Definition Simulator.h:484
void AddActorTorque(const Actor &actor, const geom::Vector3D &torque)
给指定演员施加扭矩
Definition Simulator.h:476
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id, bool replay_sensors)
Definition Simulator.h:696
std::vector< rpc::EnvironmentObject > GetEnvironmentObjects(uint8_t queried_tag) const
Definition Simulator.h:309
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:305
void EnableChronoPhysics(Vehicle &vehicle, uint64_t MaxSubsteps, float MaxSubstepDeltaTime, std::string VehicleJSON, std::string PowertrainJSON, std::string TireJSON, std::string BaseJSONPath)
Definition Simulator.h:645
void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime)
Definition Simulator.h:772
void UseCarSimRoad(Vehicle &vehicle, bool enabled)
Definition Simulator.h:641
std::string StartRecorder(std::string name, bool additional_data)
Definition Simulator.h:672
time_duration GetNetworkingTimeout()
Definition Simulator.h:189
rpc::WeatherParameters GetWeatherParameters()
Definition Simulator.h:273
std::vector< geom::Transform > GetActorBoneRelativeTransforms(const Actor &actor)
Definition Simulator.h:496
void ApplyPhysicsControlToVehicle(Vehicle &vehicle, const rpc::VehiclePhysicsControl &physicsControl)
Definition Simulator.h:612
std::vector< std::string > GetActorSocketNames(const Actor &actor)
Definition Simulator.h:516
void OpenVehicleDoor(Vehicle &vehicle, const rpc::VehicleDoor door_idx)
Definition Simulator.h:620
void UnloadLevelLayer(rpc::MapLayer map_layers) const
Definition Simulator.h:83
geom::Location GetActorLocation(const Actor &actor) const
Definition Simulator.h:422
void SetActorTransform(Actor &actor, const geom::Transform &transform)
Definition Simulator.h:525
void EnableActorConstantVelocity(const Actor &actor, const geom::Vector3D &vector)
启用演员的恒定速度(用于模拟持续的线性运动)
Definition Simulator.h:447
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:426
boost::optional< rpc::Actor > GetActorById(ActorId id) const
Definition Simulator.h:361
void LoadLevelLayer(rpc::MapLayer map_layers) const
Definition Simulator.h:79
void RegisterAIController(const WalkerAIController &controller)
void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition Simulator.h:576
void SetIMUISensorGravity(float NewIMUISensorGravity)
Definition Simulator.h:290
void ApplyBatch(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition Simulator.h:817
SharedPtr< LightManager > _light_manager
Definition Simulator.h:900
void RemoveOnTickEvent(size_t id)
Definition Simulator.h:215
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="")
在模拟中生成一个参与者
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:588
SharedPtr< Actor > MakeActor(rpc::Actor actor_description, GarbageCollectionPolicy gc=GarbageCollectionPolicy::Disabled)
根据现有参与者的描述创建一个参与者实例。请注意,这不会生成参与者。
Definition Simulator.h:381
void UpdateDayNightCycle(const bool active) const
Definition Simulator.h:852
bool IsEnabledForROS(const Sensor &sensor)
void SetBonesTransform(Walker &walker, const rpc::WalkerBoneControlIn &bones)
Definition Simulator.h:600
size_t RegisterOnTickEvent(std::function< void(WorldSnapshot)> callback)
Definition Simulator.h:210
SharedPtr< BlueprintLibrary > GetBlueprintLibrary()
void UpdateServerLightsState(std::vector< rpc::LightState > &lights, bool discard_client=false) const
Definition Simulator.h:845
std::vector< std::string > GetActorBoneNames(const Actor &actor)
Definition Simulator.h:504
std::vector< geom::Transform > GetActorBoneWorldTransforms(const Actor &actor)
Definition Simulator.h:492
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:314
const GarbageCollectionPolicy _gc_policy
Definition Simulator.h:906
void SetActorSimulatePhysics(Actor &actor, bool enabled)
Definition Simulator.h:529
std::vector< std::string > GetAvailableMaps()
Definition Simulator.h:146
void SetActorEnableGravity(Actor &actor, bool enabled)
Definition Simulator.h:549
void SetLightsToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control)
Definition Simulator.h:572
void SetWeatherParameters(const rpc::WeatherParameters &weather)
Definition Simulator.h:278
rpc::VehicleLightStateList GetVehiclesLightStates()
返回一个列表,其中第一个元素是车辆 ID,第二个元素是灯光状态
bool DestroyActor(ActorId actor_id)
Definition Simulator.h:404
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:608
std::string ShowRecorderCollisions(std::string name, char type1, char type2)
Definition Simulator.h:688
auto ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue)
Definition Simulator.h:822
void UnregisterAIController(const WalkerAIController &controller)
void BlendPose(Walker &walker, float blend)
Definition Simulator.h:604
void SetLightStateToVehicle(Vehicle &vehicle, const rpc::VehicleLightState light_state)
Definition Simulator.h:616
void SetActorDead(Actor &actor)
Definition Simulator.h:541
void ResetTrafficLightGroup(TrafficLight &trafficLight)
Definition Simulator.h:784
void SetReplayerIgnoreHero(bool ignore_hero)
Definition Simulator.h:706
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)
– 纹理更新操作
void DrawDebugShape(const rpc::DebugShape &shape)
Definition Simulator.h:806
std::vector< std::string > GetActorComponentNames(const Actor &actor)
Definition Simulator.h:500
std::shared_ptr< WalkerNavigation > GetNavigation()
geom::Vector3D GetActorAcceleration(const Actor &actor) const
获取指定演员的加速度
Definition Simulator.h:480
bool SetFilesBaseFolder(const std::string &path)
SharedPtr< Actor > GetSpectator()
std::vector< rpc::LightState > QueryLightsStateToServer() const
Definition Simulator.h:838
geom::Vector3D GetActorVelocity(const Actor &actor) const
获取指定演员的速度(可能包括线性速度和角速度)
Definition Simulator.h:431
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:564
uint64_t SetEpisodeSettings(const rpc::EpisodeSettings &settings)
void EnableCarSim(Vehicle &vehicle, std::string simfile_path)
Definition Simulator.h:637
size_t RegisterLightUpdateChangeEvent(std::function< void(WorldSnapshot)> callback)
Definition Simulator.h:857
bool IsTrafficManagerRunning(uint16_t port) const
查询交通管理器是否正在端口上运行
Definition Simulator.h:233
void SetWheelSteerDirection(Vehicle &vehicle, rpc::VehicleWheelLocation wheel_location, float angle_in_deg)
Definition Simulator.h:628
void SetNetworkingTimeout(time_duration timeout)
Definition Simulator.h:185
void SetActorLocation(Actor &actor, const geom::Location &location)
设置 Actor 状态
Definition Simulator.h:521
SharedPtr< LightManager > GetLightManager() const
Definition Simulator.h:833
std::pair< std::string, uint16_t > GetTrafficManagerRunning(uint16_t port) const
获取一个填充了在端口上运行的交通管理器的 <IP, 端口> 对。 如果没有正在运行的流量管理器,则该对将为 ("", 0)
Definition Simulator.h:239
std::vector< rpc::Actor > GetActorsById(const std::vector< ActorId > &actor_ids) const
根据一组演员ID获取对应的演员信息
Definition Simulator.h:366
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
Definition Simulator.h:692
void UnSubscribeFromSensor(Actor &sensor)
EpisodeProxy LoadEpisode(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layers=rpc::MapLayer::All)
Definition Simulator.cpp:88
rpc::AckermannControllerSettings GetAckermannControllerSettings(const Vehicle &vehicle) const
Definition Simulator.h:584
void ApplyAckermannControlToVehicle(Vehicle &vehicle, const rpc::VehicleAckermannControl &control)
Definition Simulator.h:580
void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime)
Definition Simulator.h:776
void RemoveLightUpdateChangeEvent(size_t id)
Definition Simulator.h:862
void RestorePhysXPhysics(Vehicle &vehicle)
Definition Simulator.h:661
WorldSnapshot GetWorldSnapshot() const
Definition Simulator.h:130
void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze)
Definition Simulator.h:780
uint64_t Tick(time_duration timeout)
void SetActorTargetVelocity(const Actor &actor, const geom::Vector3D &vector)
设置指定演员的目标速度
Definition Simulator.h:435
std::vector< rpc::LabelledPoint > CastRay(geom::Location start_location, geom::Location end_location) const
Definition Simulator.h:328
void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse)
给指定演员施加脉冲力
Definition Simulator.h:455
void AddActorForce(const Actor &actor, const geom::Vector3D &force, const geom::Vector3D &location)
给指定演员在特定位置施加持续的力
Definition Simulator.h:468
void AddActorImpulse(const Actor &actor, const geom::Vector3D &impulse, const geom::Vector3D &location)
给指定演员在特定位置施加脉冲力
Definition Simulator.h:460
void SubscribeToGBuffer(Actor &sensor, uint32_t gbuffer_id, std::function< void(SharedPtr< sensor::SensorData >)> callback)
void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime)
Definition Simulator.h:768
ActorSnapshot GetActorSnapshot(ActorId actor_id) const
Definition Simulator.h:409
void StopReplayer(bool keep_actors)
Definition Simulator.h:714
void AddActorForce(const Actor &actor, const geom::Vector3D &force)
给指定演员施加持续的力
Definition Simulator.h:464
geom::Vector3D GetActorAngularVelocity(const Actor &actor) const
获取指定演员的角速度
Definition Simulator.h:439
std::pair< bool, rpc::LabelledPoint > ProjectPoint(geom::Location location, geom::Vector3D direction, float search_distance) const
Definition Simulator.h:321
GarbageCollectionPolicy GetGarbageCollectionPolicy() const
Definition Simulator.h:174
void SetActorCollisions(ActorId actor_id, bool enabled)
Definition Simulator.h:537
std::vector< std::string > GetNamesOfAllObjects() const
void SetReplayerTimeFactor(double time_factor)
Definition Simulator.h:701
SharedPtr< Map > GetCurrentMap()
bool AddTrafficManagerRunning(std::pair< std::string, uint16_t > trafficManagerInfo) const
通知交通管理器正在 <IP, 端口> 上运行
Definition Simulator.h:244
geom::Transform GetActorComponentRelativeTransform(const Actor &actor, std::string componentName)
获取指定演员组件的相对坐标变换信息
Definition Simulator.h:488
rpc::VehiclePhysicsControl GetVehiclePhysicsControl(const Vehicle &vehicle) const
Definition Simulator.h:295
void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled=true)
Definition Simulator.h:568
rpc::EpisodeSettings GetEpisodeSettings()
Definition Simulator.h:267
ActorSnapshot GetActorSnapshot(const Actor &actor) const
Definition Simulator.h:414
bool DestroyActor(Actor &actor)
销毁指定的演员
std::vector< geom::Transform > GetActorSocketWorldTransforms(const Actor &actor)
Definition Simulator.h:508
void SetPedestriansSeed(unsigned int seed)
void DisableActorConstantVelocity(const Actor &actor)
禁用演员的恒定速度
Definition Simulator.h:451
std::vector< geom::BoundingBox > GetLightBoxes(const TrafficLight &trafficLight) const
Definition Simulator.h:792
boost::optional< geom::Location > GetRandomLocationFromNavigation()
void Send(const Sensor &sensor, std::string message)
void SetActorDead(ActorId actor_id)
Definition Simulator.h:545
std::string ShowRecorderFileInfo(std::string name, bool show_all)
Definition Simulator.h:683
std::vector< ActorId > GetGroupTrafficLights(TrafficLight &trafficLight)
Definition Simulator.h:796
void SetReplayerIgnoreSpectator(bool ignore_spectator)
Definition Simulator.h:710
定义车辆的物理外观,通过传感器获取
Positive time duration up to milliseconds resolution.
Definition Time.h:19
std::vector< std::pair< ActorId, VehicleLightState::flag_type > > VehicleLightStateList
carla::ActorId ActorId
参与者的智能指针类型
CARLA模拟器的主命名空间。
Definition Carla.cpp:139
boost::shared_ptr< T > SharedPtr
使用这个SharedPtr(boost::shared_ptr)以保持与boost::python的兼容性, 但未来如果可能的话,我们希望能为std::shared_ptr制作一个Python适配器。
Definition Memory.h:19
包含CARLA客户端相关类和函数的命名空间。
Seting for map generation from opendrive without additional geometry