CARLA
 
载入中...
搜索中...
未找到
client/Client.h
浏览该文件的文档.
1// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
2// de Barcelona (UAB).
3//
4// 参考PythonAPI:https://openhutb.github.io/carla_doc/python_api/
5//
6// This work is licensed under the terms of the MIT license.
7// For a copy, see <https://opensource.org/licenses/MIT>.
8
9#pragma once
10
11#include "carla/client/detail/Simulator.h" // 引入Simulator相关的头文件,用于控制和模拟仿真环境中的车辆、传感器等。
12#include "carla/client/World.h" // 引入World相关的头文件,提供了对CARLA模拟世界的访问接口,包括控制和交互等功能。
13#include "carla/client/Map.h" // 引入Map相关的头文件,用于访问和操作CARLA世界中的地图。
14#include "carla/PythonUtil.h" // 引入PythonUtil头文件,这通常用于将C++与Python代码交互或提供Python脚本的调用接口。
15#include "carla/trafficmanager/TrafficManager.h" // 引入TrafficManager相关的头文件,用于管理交通流量并控制自动驾驶行为。
16
17namespace carla {
18namespace client {
19
20 using namespace carla::traffic_manager;
21
22 class Client {
23 public:
24
25 /// 构建一个 carla 客户端。
26 ///
27 /// @param host 运行模拟器的主机IP地址。
28 /// @param port 连接到模拟器的TCP端口。
29 /// @param worker_threads 要使用的异步线程数,默认为 0(即使用所有可用的硬件并发线程)。
30 explicit Client(
31 const std::string &host,
32 uint16_t port,
33 size_t worker_threads = 0u);
34
35 /// 设置网络操作的超时时间。超时将抛出 rpc::timeout 异常
36 void SetTimeout(time_duration timeout) {
37 _simulator->SetNetworkingTimeout(timeout);
38 }
39
40 // 获取当前客户端的网络超时时间。
42 return _simulator->GetNetworkingTimeout();
43 }
44
45 /// 返回此客户端 API 版本的字符串。
46 std::string GetClientVersion() const {
47 return _simulator->GetClientVersion();
48 }
49
50 /// 获取当前连接的模拟器版本字符串。
51 std::string GetServerVersion() const {
52 return _simulator->GetServerVersion();
53 }
54
55 /// 获取当前服务中心提供的所有可用地图名称。
56 std::vector<std::string> GetAvailableMaps() const {
57 return _simulator->GetAvailableMaps();
58 }
59 /// 设置文件系统的基路径(文件夹)。
60 /// 用于设置模拟器读取文件的路径。
61 /// 返回操作是否成功。
62 bool SetFilesBaseFolder(const std::string &path) {
63 return _simulator->SetFilesBaseFolder(path);
64 }
65 /// 获取指定文件夹中的所需文件列表,默认情况下会下载所需文件。
66 /// 如果文件夹路径为空,则使用默认路径。
67 std::vector<std::string> GetRequiredFiles(const std::string &folder = "", const bool download = true) const {
68 return _simulator->GetRequiredFiles(folder, download);
69 }
70 /// 请求指定名称的文件,模拟器会处理文件的加载或下载。
71 void RequestFile(const std::string &name) const {
72 _simulator->RequestFile(name);
73 }
74 /// 重新加载世界环境。
75 /// 通过调用 _simulator->ReloadEpisode 来实现,是否重置设置由参数决定。
76 /// 返回重载后的世界对象。
77 World ReloadWorld(bool reset_settings = true) const {
78 return World{_simulator->ReloadEpisode(reset_settings)};
79 }
80
81 /// 加载指定名称的场景地图。
82 /// @param map_name 地图名称。
83 /// @param reset_settings 是否重置设置。
84 /// @param map_layers 需要加载的地图层。
86 std::string map_name, // 地图名
87 bool reset_settings = true,
88 // 实际调用 _simulator->LoadEpisode 返回的场景
89 rpc::MapLayer map_layers = rpc::MapLayer::All) const {
90 return World{_simulator->LoadEpisode(std::move(map_name), reset_settings, map_layers)};
91 }
92
93 /// 如果当前地图与请求地图不同,则加载新地图。
95 std::string map_name,
96 bool reset_settings = true,
97 rpc::MapLayer map_layers = rpc::MapLayer::All) const {
99 carla::SharedPtr<carla::client::Map> current_map = world.GetMap();
100 std::string current_map_name = current_map->GetName();
101 std::string map_name_prefix = "Carla/Maps/";
102 std::string map_name_without_prefix = map_name;
103 std::string map_name_with_prefix = map_name_prefix + map_name;
104 // 仅当当前地图不同于目标地图时,才重新加载世界
105 if(!(map_name_without_prefix == current_map_name) && !(map_name_with_prefix == current_map_name)){
106 World World{_simulator->LoadEpisode(std::move(map_name), reset_settings, map_layers)};
107 }else{}
108 }
109
110 /// 通过 OpenDrive 文件生成一个新的世界。
111 /// @param opendrive OpenDrive 格式的文件路径。
112 /// @param params 生成 OpenDrive 世界时的参数。
113 /// @param reset_settings 是否重置设置。
115 std::string opendrive,
117 bool reset_settings = true) const {
118 return World{_simulator->LoadOpenDriveEpisode(
119 std::move(opendrive), params, reset_settings)};
120 }
121
122 /// 获取当前模拟器中的活跃世界实例。
123 World GetWorld() const {
124 return World{_simulator->GetCurrentEpisode()};
125 }
126
127 /// 获取当前模拟器中的 TrafficManager 实例。
128 /// @param port TrafficManager 使用的端口,默认为 TM_DEFAULT_PORT。
129 TrafficManager GetInstanceTM(uint16_t port = TM_DEFAULT_PORT) const {
130 return TrafficManager(_simulator->GetCurrentEpisode(), port);
131 }
132
133 /// 获取当前模拟器中的活动场景实例。
135 return _simulator->GetCurrentEpisode();
136 }
137
138 // 启动录像功能,开始记录服务器重放仿真所需的所有信息。
139 std::string StartRecorder(std::string name, bool additional_data = false) {
140 return _simulator->StartRecorder(name, additional_data);
141 }
142
143 // 停止记录并保存日志数据。
144 void StopRecorder(void) {
145 _simulator->StopRecorder();
146 }
147
148 // 显示指定记录文件的详细信息。
149 /// @param name 文件名。
150 /// @param show_all 是否显示所有记录信息。
151 std::string ShowRecorderFileInfo(std::string name, bool show_all) {
152 return _simulator->ShowRecorderFileInfo(name, show_all);
153 }
154
155 // 在终端中显示记录器记录的碰撞。
156 // 可以通过指定所涉及参与者的类型来过滤这些内容。
157 // 类别将在`type1`和`type2`中指定:
158 // `h`表示英雄参与者,一种可以手动控制或由用户管理的车辆。
159 // `v`表示车辆,`w`表示行人,`t`表示红绿灯,`o`表示其他,`a`表示所有。
160 // 如果您只想看到车辆和行人之间的碰撞,请将`category1`设置为`v`,将`category2`设置为`w`,反之亦然。
161 // 如果要查看所有碰撞(过滤掉),可以对两个参数都使用`a`。
162 std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
163 return _simulator->ShowRecorderCollisions(name, type1, type2);
164 }
165
166 // 在终端中显示视为被堵塞的参与者注册信息。
167 // 当参与者在一段时间 min_time 内没有移动最小距离 min_distance 时,则视为被堵塞。
168 std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
169 return _simulator->ShowRecorderActorsBlocked(name, min_time, min_distance);
170 }
171
172 // 解析记录器保存的信息将并以文本形式显示在终端中(帧、时间、事件、状态、位置…)。
173 std::string ReplayFile(std::string name, double start, double duration,
174 uint32_t follow_id, bool replay_sensors) {
175 return _simulator->ReplayFile(name, start, duration, follow_id, replay_sensors);
176 }
177
178 // 停止当前的重放过程。
179 void StopReplayer(bool keep_actors) {
180 _simulator->StopReplayer(keep_actors);
181 }
182
183 // 使用时,会随意修改重新模拟的时间速度。当播放时,它可以使用多次。
184 // 1.0表示正常时间速度。大于1.0表示快速运动(2.0表示双倍速度),小于1.0表示慢速运动(0.5表示一半速度)。
185 void SetReplayerTimeFactor(double time_factor) {
186 _simulator->SetReplayerTimeFactor(time_factor);
187 }
188
189 // ignore_hero:在播放记录的模拟过程中启用或禁用英雄车辆的播放。
190 void SetReplayerIgnoreHero(bool ignore_hero) {
191 _simulator->SetReplayerIgnoreHero(ignore_hero);
192 }
193
194 // 确定回放程序是否会复制记录的观察者运动。
195 void SetReplayerIgnoreSpectator(bool ignore_spectator) {
196 _simulator->SetReplayerIgnoreSpectator(ignore_spectator);
197 }
198
199 // 在单个模拟步上执行命令列表,不检索任何信息。
201 std::vector<rpc::Command> commands,
202 bool do_tick_cue = false) const {
203 _simulator->ApplyBatch(std::move(commands), do_tick_cue);
204 }
205
206 // 在单个模拟步上阻塞式地执行命令列表,直到命令链接起来,并返回 command.Response 列表。
207 // 可用于确定单个命令是否成功的响应。
208 std::vector<rpc::CommandResponse> ApplyBatchSync(
209 std::vector<rpc::Command> commands, // 要批量执行的命令列表。
210 bool do_tick_cue = false) const { // 是否在执行后触发 tick 事件。
211 auto responses = _simulator->ApplyBatchSync(std::move(commands), false);
212 if (do_tick_cue)
213 _simulator->Tick(_simulator->GetNetworkingTimeout());
214
215 return responses; // 返回所有命令的响应列表。
216 }
217
218 private:
219
220 // 当前仿真器实例的智能指针,用于管理仿真器的生命周期。
221 std::shared_ptr<detail::Simulator> _simulator;
222 };
223
224 // Client 构造函数,初始化与仿真器的连接。
226 const std::string &host, // 仿真器主机地址。
227 uint16_t port, // 仿真器端口号。
228 size_t worker_threads) // 使用的工作线程数量。
229 : _simulator(
230 new detail::Simulator(host, port, worker_threads),
231 PythonUtil::ReleaseGILDeleter()) {} // 初始化仿真器并传递 GIL 解锁器以支持 Python 集成。
232
233} // namespace client
234} // namespace carla
void RequestFile(const std::string &name) const
请求指定名称的文件,模拟器会处理文件的加载或下载。
std::string GetServerVersion() const
获取当前连接的模拟器版本字符串。
World LoadWorld(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layers=rpc::MapLayer::All) const
加载指定名称的场景地图。
time_duration GetTimeout()
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance)
bool SetFilesBaseFolder(const std::string &path)
设置文件系统的基路径(文件夹)。 用于设置模拟器读取文件的路径。 返回操作是否成功。
carla::client::detail::EpisodeProxy GetCurrentEpisode() const
获取当前模拟器中的活动场景实例。
Client(const std::string &host, uint16_t port, size_t worker_threads=0u)
构建一个 carla 客户端。
void SetReplayerIgnoreSpectator(bool ignore_spectator)
World GetWorld() const
获取当前模拟器中的活跃世界实例。
std::shared_ptr< detail::Simulator > _simulator
std::vector< std::string > GetAvailableMaps() const
获取当前服务中心提供的所有可用地图名称。
void LoadWorldIfDifferent(std::string map_name, bool reset_settings=true, rpc::MapLayer map_layers=rpc::MapLayer::All) const
如果当前地图与请求地图不同,则加载新地图。
void SetReplayerTimeFactor(double time_factor)
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id, bool replay_sensors)
World GenerateOpenDriveWorld(std::string opendrive, const rpc::OpendriveGenerationParameters &params, bool reset_settings=true) const
通过 OpenDrive 文件生成一个新的世界。
World ReloadWorld(bool reset_settings=true) const
重新加载世界环境。 通过调用 _simulator->ReloadEpisode 来实现,是否重置设置由参数决定。 返回重载后的世界对象。
std::string StartRecorder(std::string name, bool additional_data=false)
void ApplyBatch(std::vector< rpc::Command > commands, bool do_tick_cue=false) const
void SetReplayerIgnoreHero(bool ignore_hero)
void StopReplayer(bool keep_actors)
std::vector< std::string > GetRequiredFiles(const std::string &folder="", const bool download=true) const
获取指定文件夹中的所需文件列表,默认情况下会下载所需文件。 如果文件夹路径为空,则使用默认路径。
std::string GetClientVersion() const
返回此客户端 API 版本的字符串。
void SetTimeout(time_duration timeout)
设置网络操作的超时时间。超时将抛出 rpc::timeout 异常
std::string ShowRecorderCollisions(std::string name, char type1, char type2)
std::string ShowRecorderFileInfo(std::string name, bool show_all)
TrafficManager GetInstanceTM(uint16_t port=TM_DEFAULT_PORT) const
获取当前模拟器中的 TrafficManager 实例。
std::vector< rpc::CommandResponse > ApplyBatchSync(std::vector< rpc::Command > commands, bool do_tick_cue=false) const
SharedPtr< Map > GetMap() const
返回描述这个世界的地图。 返回的是一个智能指针指向的Map对象,该Map对象包含了模拟世界中的地理信息、道路布局等地图相关的数据结构, 供外部调用者进一步查询和操作地图相关的功能。
Definition World.cpp:24
Positive time duration up to milliseconds resolution.
Definition Time.h:19
该类通过使用消息传递机制,将交通管理器的各个阶段恰当地整合在一起
Carla项目的交通管理命名空间。
Definition Vehicle.h:68
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