开发者说 | Apollo项目代码迁移到Cyber RT框架的方法
Apollo 3.5是一个全新的代码仓库,与之前的版本几乎不兼容,不能在原有代码的基础上更新,而必须重新从GitHub仓库重新下载代码。
同时,Apollo 3.5彻底摒弃ROS,改用自研的Cyber RT作为底层通讯与调度平台,实时性与灵活性更为突出。
关于《Apollo 3.5的构建方法》,可参见社区荣誉布道师—贺博士的一篇博客。关于《Apollo 3.5各功能模块的启动过程解析》,可参见其另一篇博客。
感谢贺博士的本篇文章为我们阐述了Apollo项目代码迁移到Cyber RT框架(Apollo 3.5以上版本)的方法。
阿波君希望这篇文给感兴趣的同学带来更多帮助。
本文在Apollo官方文档《How to create and run a new component in Apollo Cyber RT》及《How to use Cyber commands》的基础上撰写,但更为翔实具体。
Apollo Cyber RT框架基于组件的概念构建、加载各功能模块。
Localization、 Perception、Prediction、Planning、Control等功能模块均作为Apollo Cyber RT框架的一个组件而存在,基于Cyber RT提供的调度程序Mainboard加载运行。
基于Apollo Cyber RT框架创建和发布新的功能模块组件,需执行以下五个基本步骤:
设置组件文件结构
实现组件类
提供构建文件
提供配置文件
启动组件
下面以Planning模块为例进行阐述。
基于路径${APOLLO_HOME}/modules/planning(${APOLLO_HOME}表示Apollo项目的根目录,以我的机器为例。
Docker外部为/home/davidhopper/code/apollo,Docker内部自不必说,全部为/apollo。
为描述简单起见,下文全部以Docker内部的路径/apollo为准)设置如下组件文件结构:
头文件: planning_component.h;
实现文件: planning_component.cc;
构建文件: BUILD;
DAG配置文件: dag/planning.dag;
Launch配置文件: launch/planning.launch。
执行以下步骤以实现组件类:
基于模板类Component派生出规划模块的组件类PlanningComponent;
在派生类PlanningComponent中重载虚函数Init()&Proc()函数;
使用宏 CYBER_REGISTER_COMPONENT(PlanningComponent) 注册组件类 PlanningComponent,以便Cyber RT能正确创建并加载该类对象(关于该宏的具体含义,参见我的博客Apollo 3.5各功能模块的启动过程解析)。
1namespace apollo {
2namespace planning {
3
4class PlanningComponent final
5 : public cyber::Component<prediction::predictionobstacles, canbus::chassis,
6 localization::LocalizationEstimate> {
7 public:
8 PlanningComponent() = default;
9
10 ~PlanningComponent() = default;
11
12 public:
13 bool Init() override;
14
15 bool Proc(const std::shared_ptr<:predictionobstacles>&
16 prediction_obstacles,
17 const std::shared_ptr<:chassis>& chassis,
18 const std::shared_ptr<localization::localizationestimate>&
19 localization_estimate)</localization::localizationestimate> override;
20
21 private:
22 void CheckRerouting();
23 bool CheckInput();
24
25 std::shared_ptr<cyber::reader< span=""><perception::trafficlightdetection>>
26 traffic_light_reader_;
27 std::shared_ptr<cyber::reader< span=""><:routingresponse>> routing_reader_;
28 std::shared_ptr<cyber::reader< span=""><:padmessage>> pad_message_reader_;
29 std::shared_ptr<cyber::reader< span=""><:mapmsg>> relative_map_reader_;
30
31 std::shared_ptr<cyber::writer< span="">> planning_writer_;
32 std::shared_ptr<cyber::writer< span=""><:routingrequest>> rerouting_writer_;
33
34 std::mutex mutex_;
35 perception::TrafficLightDetection traffic_light_;
36 routing::RoutingResponse routing_;
37 PadMessage pad_message_;
38 relative_map::MapMsg relative_map_;
39
40 LocalView local_view_;
41
42 std::unique_ptr planning_base_;
43
44 PlanningConfig config_;
45};
46
47CYBER_REGISTER_COMPONENT(PlanningComponent)
48
49} // namespace planning
50} // namespace apollo
</perception::trafficlightdetection>
注意到基类Component的定义为:
1template <typename M0 = NullType, typename M1 = NullType,
2 typename M2 = NullType, typename M3 = NullType>
3class Component : public ComponentBase {
4 // ...
5};
可见,Component 类最多接受4个模板参数,每个模板参数均表示一种输入的消息类型。
这些消息在Proc函数中被周期性地接收并处理;
而PlanningComponent继承的是该模板类接受3个参数的一个特化版本:
1template <typename M0, typename M1, typename M2>
2class Component : ,> public ComponentBase {
3 // ...
4};
即PlanningComponent继承自
cyber::Component<prediction::predictionobstacles< span="">,
canbus::Chassis, localization::LocalizationEstimate>,
3个消息参数分别为:prediction::PredictionObstacles、
canbus::Chassis、localization::LocalizationEstimate,
这些消息在Proc函数中被周期性地接收并处理。
PlanningComponent的实现主要包括两个重载的虚函数Init() & Proc()函数:
1bool PlanningComponent::Init() {
2 if (FLAGS_open_space_planner_switchable) {
3 planning_base_ = std::unique_ptr(new OpenSpacePlanning());
4 } else {
5 planning_base_ = std::unique_ptr(new StdPlanning());
6 }
7 CHECK(apollo::common::util::GetProtoFromFile(FLAGS_planning_config_file,
8 &config_))
9 << "failed to load planning config file " << FLAGS_planning_config_file;
10 planning_base_->Init(config_);
11
12 if (FLAGS_use_sim_time) {
13 Clock::SetMode(Clock::MOCK);
14 }
15 routing_reader_ = node_->CreateReader(
16 FLAGS_routing_response_topic,
17 [this](const std::shared_ptr& routing) {
18 AINFO << "Received routing data: run routing callback."
19 << routing->header().DebugString();
20 std::lock_guard<:mutex> lock(mutex_);
21 routing_.CopyFrom(*routing);
22 });
23 traffic_light_reader_ = node_->CreateReader(
24 FLAGS_traffic_light_detection_topic,
25 [this](const std::shared_ptr& traffic_light) {
26 ADEBUG << "Received traffic light data: run traffic light callback.";
27 std::lock_guard<:mutex> lock(mutex_);
28 traffic_light_.CopyFrom(*traffic_light);
29 });
30
31 if (FLAGS_use_navigation_mode) {
32 pad_message_reader_ = node_->CreateReader(
33 FLAGS_planning_pad_topic,
34 [this](const std::shared_ptr& pad_message) {
35 ADEBUG << "Received pad data: run pad callback.";
36 std::lock_guard<:mutex> lock(mutex_);
37 pad_message_.CopyFrom(*pad_message);
38 });
39 relative_map_reader_ = node_->CreateReader(
40 FLAGS_relative_map_topic,
41 [this](const std::shared_ptr& map_message) {
42 ADEBUG << "Received relative map data: run relative map callback.";
43 std::lock_guard<:mutex> lock(mutex_);
44 relative_map_.CopyFrom(*map_message);
45 });
46 }
47 planning_writer_ =
48 node_->CreateWriter(FLAGS_planning_trajectory_topic);
49
50 rerouting_writer_ =
51 node_->CreateWriter(FLAGS_routing_request_topic);
52
53 return true;
54}
其中Init()函数用于创建实际规划类对象。
创建除prediction::PredictionObstacles、canbus::Chassis、
localization::LocalizationEstimate
三类消息以外的其他消息处理回调函数,
创建Planning模块的输出器:
轨迹输出器planning_writer_和重新生成路由输出器rerouting_writer_。
注意目前(2019年1月7日)版本
并未创建导航模式规划器NaviPlanning。
1bool PlanningComponent::Proc(
2 const std::shared_ptr<:predictionobstacles>&
3 prediction_obstacles,
4 const std::shared_ptr<:chassis>& chassis,
5 const std::shared_ptr<localization::localizationestimate>&
6 localization_estimate) {
7 CHECK(prediction_obstacles != nullptr);
8
9 if (FLAGS_use_sim_time) {
10 Clock::SetNowInSeconds(localization_estimate->header().timestamp_sec());
11 }
12 // check and process possible rerouting request
13 CheckRerouting();
14
15 // process fused input data
16 local_view_.prediction_obstacles = prediction_obstacles;
17 local_view_.chassis = chassis;
18 local_view_.localization_estimate = localization_estimate;
19 {
20 std::lock_guard<std::mutex> lock(mutex_);
21 if (!local_view_.routing ||
22 hdmap::PncMap::IsNewRouting(*local_view_.routing, routing_)) {
23 local_view_.routing =
24 std::make_shared<:routingresponse>(routing_);
25 local_view_.is_new_routing = true;
26 } else {
27 local_view_.is_new_routing = false;
28 }
29 }
30 {
31 std::lock_guard<std::mutex> lock(mutex_);
32 local_view_.traffic_light =
33 std::make_shared(traffic_light_);
34 }
35
36 if (!CheckInput()) {
37 AERROR << "Input check failed";
38 return false;
39 }
40
41 ADCTrajectory adc_trajectory_pb;
42 planning_base_->RunOnce(local_view_, &adc_trajectory_pb);
43 auto start_time = adc_trajectory_pb.header().timestamp_sec();
44 common::util::FillHeader(node_->Name(), &adc_trajectory_pb);
45
46 // modify trajecotry relative time due to the timestamp change in header
47 const double dt = start_time - adc_trajectory_pb.header().timestamp_sec();
48 for (auto& p : *adc_trajectory_pb.mutable_trajectory_point()) {
49 p.set_relative_time(p.relative_time() + dt);
50 }
51 planning_writer_->Write(std::make_shared(adc_trajectory_pb));
52 return true;
53} </<:predictionobstacles><:chassis>localization::localizationestimate><:predictionobstacles><:chassis>
而Proc()函数周期性地接收
prediction::PredictionObstacles、canbus::Chassis、
localization::LocalizationEstimate三类消息。
调用planning_base_->RunOnce()函数
执行实际的路径与速度规划,
并将规划结果adc_trajectory_pb借助
函数planning_writer_->Write()将生成的规划轨迹输出给控制模块执行。
1.3 提供构建文件
/apollo/modules/planning/BUILD
下面列出/apollo/modules/planning/BUILD文件中与Cyber RT相关的内容。
可见基于planning_component_lib库
最终生成一个共享库文件libplanning_component.so。
而该共享库通过Cyber RT调度程序mainboard动态加载运行:
1load("//tools:cpplint.bzl", "cpplint")
2
3package(default_visibility = ["//visibility:public"])
4
5cc_library(
6 name = "planning_component_lib",
7 srcs = [
8 "planning_component.cc",
9 ],
10 hdrs = [
11 "planning_component.h",
12 ],
13 copts = [
14 "-DMODULE_NAME=\\\"planning\\\"",
15 ],
16 deps = [
17 ":planning_lib",
18 "//cyber",
19 "//modules/common/adapters:adapter_gflags",
20 "//modules/common/util:message_util",
21 "//modules/localization/proto:localization_proto",
22 "//modules/map/relative_map/proto:navigation_proto",
23 "//modules/perception/proto:perception_proto",
24 "//modules/planning/proto:planning_proto",
25 "//modules/prediction/proto:prediction_proto",
26 ],
27)
28
29cc_binary(
30 name = "libplanning_component.so",
31 linkshared = True,
32 linkstatic = False,
33 deps = [":planning_component_lib"],
34)
1.4 提供DAG配置文件:
/apollo/dag/planning.dag
DAG配置文件是Cyber RT调度程序
mainboard动态加载Planning模块的最终配置文件,加载命令一般为:
1/apollo/bazel-bin/cyber/mainboard -d /apollo/modules/planning/dag/planing.dag
标准模式的DAG配置文件如下:
1# Define all coms in DAG streaming.
2module_config {
3 # 共享库文件路径
4 module_library : "/apollo/bazel-bin/modules/planning/libplanning_component.so"
5 components {
6 # 组件类名称,一定不能写错,否则mainboard无法动态创建PlanningComponent组件对象
7 class_name : "PlanningComponent"
8 config {
9 # 模块名
10 name: "planning"
11 # GFlag配置文件路径
12 flag_file_path: "/apollo/modules/planning/conf/planning.conf"
13 # PlanningComponent组件Proc()函数中使用的三个消息接收器
14 readers: [
15 {
16 channel: "/apollo/prediction"
17 },
18 {
19 channel: "/apollo/canbus/chassis"
20 qos_profile: {
21 depth : 15
22 }
23 pending_queue_size: 50
24 },
25 {
26 channel: "/apollo/localization/pose"
27 qos_profile: {
28 depth : 15
29 }
30 pending_queue_size: 50
31 }
32 ]
33 }
34 }
35}
1.5 提供Launch配置文件:
/apollo/launch/planning.launch
Launch配置文件是Cyber RT提供的
一个Python工具程序cyber_launch
加载Planning模块所需的配置文件,
启动命令如下所示(最终仍归结于mainboard加载):
1cyber_launch start /apollo/launch/planning.launch
标准模式的Launch配置文件如下:
1<cyber>
2 <module>
3 <name>planningname>
4 <dag_conf>/apollo/modules/planning/dag/planning.dagdag_conf>
5 <process_name>planningprocess_name>
6 module>
7cyber>
基于Cyber RT接收消息分两种情形。
第一种是1.2.1节描述的
在虚函数PlanningComponent::Proc()中处理指定的消息类型。
这类消息是周期性触发,但最多只能接收4种
(因为cyber::Component的模板参数最多只有4个),
一般用于模块主要输入消息的接收。
第二种是直接创建消息接收器。
一般用于接收非周期性消息或模块的次要输入消息,
示例代码如下,注意消息处理回调函数
均以Lambda表达式的方式展现:
1 routing_reader_ = node_->CreateReader<RoutingResponse>(
2 FLAGS_routing_response_topic,
3 [this](const std::shared_ptr
4 AINFO << "Received routing data: run routing callback."
5 << routing->header().DebugString();
6 std::lock_guard<:mutex> lock(mutex_);
7 routing_.CopyFrom(*routing);
8 });
9 traffic_light_reader_ = node_->CreateReader<TrafficLightDetection>(
10 FLAGS_traffic_light_detection_topic,
11 [this](const std::shared_ptr
12 ADEBUG << "Received traffic light data: run traffic light callback.";
13 std::lock_guard<std::mutex> lock(mutex_);
14 traffic_light_.CopyFrom(*traffic_light);
15 });
基于Cyber RT发布消息非常直观。
首先创建发布器对象,然后填充消息,最后发布消息,示例代码如下:
1// 1.创建发布器
2<:string><:string>planning_writer_ =
3 node_->CreateWriter<ADCTrajectory>(FLAGS_planning_trajectory_topic);
4
5// 2.填充消息
6ADCTrajectory adc_trajectory_pb;
7<:string><:string>planning_base_->RunOnce(local_view_, &adc_trajectory_pb);
8<:string><:string>auto start_time = adc_trajectory_pb.header().timestamp_sec();
9<:string><:string>common::util::FillHeader(node_->Name(), &adc_trajectory_pb);
10<:string>
11<:string>// modify trajecotry relative time due to the timestamp change in header<:string>
12<:string><:string><:string><:string><:string>const double dt = start_time - adc_trajectory_pb.header().timestamp_sec();<:string><:string><:string><:string><:string>
13<:string><:string><:string><:string>for (auto& p : *a <:string><:string><:string>match <:string><:string><:string>dc_trajectory_pb.mutable_trajectory_point()) { <:string><:string><:string><:string><:string><:string><:string>
14 <:string> <:string><:string><:string><:string> p.set_relative_time(p.relative_time() + dt); <:string> <:string>
15 <:string><:string> <:string><:string><:string><:string><:string><:string>} <:string><:string> <:string>
16 <:string>
17 <:string><:string><:string><:string>// 3.发布消息 <:string>
18 <:string><:string>planning_writer_->Write(std::make_shared<ADCTrajectory>(adc_trajectory_pb));
1.8 如何在main()函数中单独使用Cyber RT?
Cyber RT可以在main()函数中单独使用,
示例代码如下,更多示例可查看Cyber Examples:
1int main(int argc, char** argv) {
2 google::ParseCommandLineFlags(&argc, &argv, true);
3 <:string><:string><:string><:string>// Init the cyber framework
4 apollo::cyber::Init(argv[0]);
5 FLAGS_alsologtostderr = true;
6
7 NavigationInfo navigation_info;
8 <:string><:string><:string><:string>// ...
9
10 std::shared_ptr<apollo::cyber::Node> node(
11 apollo::cyber::CreateNode("navigation_info"));
12 auto writer = node->CreateWriter<apollo::relative_map::NavigationInfo>(
13 FLAGS_navigation_topic);
14
15 <:string><:string><:string><:string> <:string><:string><:string><:string><:string><:string><:string><:string>// In theory, the message only needs to be sent once. Considering the problems
<:string><:string><:string><:string> 16 <:string><:string><:string><:string>// such as the network delay, We send it several times to ensure that the data
17 <:string><:string><:string><:string>// is sent successfully.
18 Rate rate(1.0);
19 constexpr int kTransNum = 3;
20 int trans_num = 0;
21 while (apollo::cyber::OK()) {
22 if (trans_num > kTransNum) {
23 break;
24 }
25 apollo::common::util::FillHeader(node->Name(), &navigation_info);
26 writer->Write(navigation_info);
27 ADEBUG << "Sending navigation info:" << navigation_info.DebugString();
28 rate.Sleep();
29 ++trans_num;
30 }
31
32 return 0;
33}
Apollo 3.0以下版本提供许多基于ROS的调试工具,
Apollo 3.5的Cyber RT框架同样提供类似功能,
下面给出常见工具的对比表:
ROS | Cyber | 备注 |
Rosbag | cyber_recorder | Data File |
scripts/diagnostics.sh(previous) | cyber_monitor | Channel Debug |
offline_lidar_vosualizer_tool | cyber_visualizer | Point Cloud Visualizer |
Record Channel
Replay Record File
1 cyber_recorder play recorder_filename
View Record File
1 cyber_recorder info recorder_filename
下面给出Apollo 3.0以下版本及Apollo 3.5以上版本的GDB调试启动命令:
1### 方法1:直接启动模块调试
2# Apollo 3.0以下版本GDB调试启动命令
3gdb -q --args bazel-bin/modules/planning/planning --flagfile=/apollo/modules/planning/conf/planning.conf
4
5# Apollo 3.5以上版本GDB调试启动命令
6gdb -q --args bazel-bin/cyber/mainboard -d modules/planning/dag/planning.dag
7
8### 方法2:通过Dreamview启动相关模块,附加调试相关进程
9# Apollo 3.0以下版本GDB调试启动命令
10# 在Dreamview中启动Planning模块,然后使用ps aux | grep planning命令查找<:string>
11<:string># planning进程ID(PID),假设为PLANNING_ID,则使用attach模式附加到当前planning进程调试<:string>
12<:string>sudo gdb -q bazel-bin/modules/planning/planning -p PLANNING_ID<:string>
13
14 <:string># # Apollo 3.5以上版本GDB调试启动命令 <:string>
15 <:string><:string># 在Dreamview中启动Planning模块,然后使用ps aux | grep mainboard命令查找 <:string>
16 <:string><:string><:string># 带有“mainboard -d /apollo/modules/planning/dag/planning.dag”描述字符的mainboard进程ID(PID), <:string>
17 <:string><:string><:string><:string># 假设为PLANNING_MODULE_ID,则使用attach模式附加到mainboard进程调试 <:string>
18 <:string><:string>sudo gdb -q bazel-bin/cyber/mainboard -p PLANNING_MODULE_ID
值得指出的是,
因为Apollo 3.5以上版本通过动态创建的方式启动Planning模块,
因此在使用GDB设置断点时,按下TAB键不会有提示,
可以借助VSCode提供的Copy Relative Path功能
撰写正确的源代码文件路径,如下图所示:
如果之前使用ROS录制了很多Bag数据包,当然不能轻易浪费这些资源。
所幸Cyber RT充分考虑到该问题,已为我们提供了转换工具rosbag_to_record。
下面将一个Apollo 2.5 Demo Bag转换为Cyber RT支持的Record格式数据包:
1rosbag_to_record demo_2.5.bag demo.record
关于该转换工具的更多描述,请参见Apollo帮助文档。
如下所示,ROS提供了直接从.bag文件读取、分析数据的功能:
1rosbag::Bag bag;
2try {
3 bag.open(bag_filename); // BagMode is Read by default
4} catch (const rosbag::BagException& e) {
5 AERROR << "Can't open the input bag file: " << bag_filename;
6 AERROR << "The reason is: " << e.what();
7 return false;
8}
9
10std::vector<:string> topics = {"/apollo/navi_generator/collector"};
11rosbag::View view(bag, rosbag::TopicQuery(topics));
12for (auto const m : view) {
13 auto msg = m.instantiate();
14 if (msg != nullptr) {
15 *min_speed_limit = msg->min_speed_limit();
16 *max_speed_limit = msg->max_speed_limit();
17 }
18}
19bag.close();
Cyber RT也提供了类似功能。
只不过ROS操作的是.bag文件,而Cyber RT操作的是.record文件,示例代码如下:
1RecordReader reader(readfile);
2RecordMessage message;
3uint64_t msg_count = reader.GetMessageNumber(CHANNEL_NAME_1);
4AINFO << "MSGTYPE: " << reader.GetMessageType(CHANNEL_NAME_1);
5AINFO << "MSGDESC: " << reader.GetProtoDesc(CHANNEL_NAME_1);
6
7// read all message
8uint64_t i = 0;
9uint64_t valid = 0;
10for (i = 0; i < msg_count; ++i) {
11 if (reader.ReadMessage(&message)) {
12 AINFO << "msg[" << i << "]-> "
13 << "channel name: " << message.channel_name
14 << "; content: " << message.content << "; msg time: " << message.time;
15 valid++;
16 } else {
17 AERROR << "read msg[" << i << "] failed";
18 }
19}
20AINFO << "static msg=================";
21AINFO << "MSG validmsg:totalcount: " << valid << ":" << msg_count;
上述代码位于/apollo/cyber/examples/record.cc文件中,其他接口可通过/apollo/cyber/record目录下的record_reader.h和record_viewer.h文件查询。
@西门吹瓶哥:
贺老师,Apollo3.5里的Planning具体轨迹还是用动态规划加QP吗?刚开始接触Apollo Planning,看之前是Em和Lattice
@知行合一2018:
Apollo 3.5以场景进行规划。
目前包括标准模式、导航模式(暂未完成迁移)、自由空间模式,EM和Latttice算法仍然包含在标准模式与导航模式中。
自Apollo平台开放已来,我们收到了大量开发者的咨询和反馈,越来越多开发者基于Apollo擦出了更多的火花,并愿意将自己的成果贡献出来,这充分体现了Apollo『贡献越多,获得越多』的开源精神。为此我们开设了『开发者说』板块,希望开发者们能够踊跃投稿,更好地为广大自动驾驶开发者营造一个共享交流的平台!
* 以上内容为开发者原创,不代表百度官方言论。
已获开发者授权,原文地址请戳阅读原文。
﹏﹏﹏﹏﹏﹏﹏﹏ END ﹏﹏﹏﹏﹏﹏﹏﹏