# 模块内容整理
## perception
### launch file
```perception_all.launch
<!--this file list the modules which will be loaded dynamicly and
their process name to be running in -->
<cyber>
<desc>cyber modules list config</desc>
<version>1.0.0</version>
<!-- sample module config, and the files should have relative path like
./bin/cyber_launch
./bin/mainboard
./conf/dag_streaming_0.conf -->
<module>
<name>perception</name>
<dag_conf>/apollo/modules/perception/production/dag/dag_streaming_perception.dag</dag_conf>
<!-- if not set, use default process -->
<process_name>perception</process_name>
<version>1.0.0</version>
</module>
<module>
<name>perception_trafficlights</name>
<dag_conf>/apollo/modules/perception/production/dag/dag_streaming_perception_trafficlights.dag</dag_conf>
<!-- if not set, use default process -->
<process_name>perception_trafficlights</process_name>
<version>1.0.0</version>
</module>
<module>
<name>motion_service</name>
<dag_conf>/apollo/modules/perception/production/dag/dag_motion_service.dag</dag_conf>
<!-- if not set, use default process -->
<process_name>motion_service</process_name>
<version>1.0.0</version>
</module>
</cyber>
```
### dag_streaming_perception.dag
#### 处理图片数据
##### FusionCameraDetectionComponent
输入:
/apollo/sensor/camera/front_6mm/image
/apollo/sensor/camera/front_12mm/image
/apollo/perception/motion_service
输出:
/perception/inner/PrefusedObjects
/perception/obstacles
/perception/inner/camera_viz_msg
/perception/camera_debug
#### 处理激光雷达数据
##### SegmentationComponent
输入:/apollo/sensor/lidar128/compensator/PointCloud2
输出:/perception/inner/SegmentationObjects
##### RecognitionComponent
输入:/perception/inner/SegmentationObjects
输出:/perception/inner/PrefusedObjects
#### 处理雷达数据
##### RadarDetectionComponent
输入:
/apollo/sensor/radar/rear
/apollo/sensor/radar/front
输出:
/perception/inner/PrefusedObjects
#### 对camera、lidar、radar三者的数据进行融合
##### FusionComponent
输入:
/perception/inner/PrefusedObjects
输出:
/perception/vehicle/obstacles
/perception/inner/visualization/FusedObjects
##### V2XFusionComponent
输入:
/perception/vehicle/obstacles
/apollo/localization/pose
/apollo/v2x/obstacles
输出:
/apollo/perception/obstacles
### dag_streaming_perception_trafficlights.dag
识别交通信号灯
#### TrafficLightsPerceptionComponent
输入:
/apollo/sensor/camera/front_6mm/image
/apollo/sensor/camera/front_12mm/image
/apollo/v2x/traffic_light
输出:
/apollo/perception/traffic_light
### dag_motion_service.dag
#### MotionService
modules/perception/camera/lib/motion_service/motion_service.cc
输入:
/apollo/sensor/camera/front_6mm/image
/apollo/localization/pose
输出:
/apollo/perception/motion_service
## prediction
### launch file
```prediction.launch
<cyber>
<module>
<name>prediction</name>
<dag_conf>/apollo/modules/prediction/dag/prediction.dag</dag_conf>
<process_name>prediction</process_name>
</module>
</cyber>
```
### prediction.dag
```
module_config {
module_library : "/apollo/bazel-bin/modules/prediction/libprediction_component.so"
components {
class_name : "PredictionComponent"
config {
name: "prediction"
config_file_path: "/apollo/modules/prediction/conf/prediction_conf.pb.txt"
flag_file_path: "/apollo/modules/prediction/conf/prediction.conf"
readers: [
{
channel: "/apollo/perception/obstacles"
qos_profile: {
depth : 1
}
}
]
}
}
}
```
#### PredictionComponent
输入:
/apollo/perception/obstacles
/apollo/planning
/apollo/localization/pose
/apollo/storytelling (storytelling 模块)
输出:
/apollo/prediction
/apollo/prediction/container
/apollo/prediction/adccontainer
/apollo/prediction/perception_obstacles

container:存储对应类型的消息
scenario:根据本车的位置,和高精度地图,解析当前车辆所在的场景
evaluator:评估障碍物的行为
predictor:预测障碍物的轨迹
模块入口位于prediction_component.cc
其中在Init函数中会初始化上述消息处理流程的四个过程
以及消息的readers和writers
```prediction_component.cc
bool PredictionComponent::Init() {
component_start_time_ = Clock::NowInSeconds();
//消息处理流程初始化
container_manager_ = std::make_shared<ContainerManager>();
evaluator_manager_.reset(new EvaluatorManager());
predictor_manager_.reset(new PredictorManager());
scenario_manager_.reset(new ScenarioManager());
PredictionConf prediction_conf;
if (!ComponentBase::GetProtoConfig(&prediction_conf)) {
AERROR << "Unable to load prediction conf file: "
<< ComponentBase::ConfigFilePath();
return false;
}
ADEBUG << "Prediction config file is loaded into: "
<< prediction_conf.ShortDebugString();
if (!MessageProcess::Init(container_manager_.get(), evaluator_manager_.get(),
predictor_manager_.get(), prediction_conf)) {
return false;
}
//预测模块数据读取
planning_reader_ = node_->CreateReader<ADCTrajectory>(
prediction_conf.topic_conf().planning_trajectory_topic(), nullptr);
//定位模块数据读取
localization_reader_ =
node_->CreateReader<localization::LocalizationEstimate>(
prediction_conf.topic_conf().localization_topic(), nullptr);
//storytelling模块数据读取
storytelling_reader_ = node_->CreateReader<storytelling::Stories>(
prediction_conf.topic_conf().storytelling_topic(), nullptr);
//预测模块数据发布
prediction_writer_ = node_->CreateWriter<PredictionObstacles>(
prediction_conf.topic_conf().prediction_topic());
container_writer_ = node_->CreateWriter<SubmoduleOutput>(
prediction_conf.topic_conf().container_topic_name());
adc_container_writer_ = node_->CreateWriter<ADCTrajectoryContainer>(
prediction_conf.topic_conf().adccontainer_topic_name());
perception_obstacles_writer_ = node_->CreateWriter<PerceptionObstacles>(
prediction_conf.topic_conf().perception_obstacles_topic_name());
return true;
}
```
上面主要调用了MessageProcess类的Init方法初始化消息处理流程,后续主要的消息处理也是通过这个类中的方法来处理的。
```message_process.cc
bool MessageProcess::Init(ContainerManager* container_manager,
EvaluatorManager* evaluator_manager,
PredictorManager* predictor_manager,
const PredictionConf& prediction_conf) {
//初始化消息容器
InitContainers(container_manager);
//初始化评估器
InitEvaluators(evaluator_manager, prediction_conf);
//初始化预测器
InitPredictors(predictor_manager, prediction_conf);
if (!FLAGS_use_navigation_mode && !PredictionMap::Ready()) {
AERROR << "Map cannot be loaded.";
return false;
}
```
OnLocalization,OnPlanning,OnStoryTelling这几个函数主要功能是往对应的消息容器中压入数据
```
void MessageProcess::OnLocalization(
ContainerManager* container_manager,
const localization::LocalizationEstimate& localization) {
auto ptr_ego_pose_container = container_manager->GetContainer<PoseContainer>(
AdapterConfig::LOCALIZATION);
ACHECK(ptr_ego_pose_container != nullptr);
ptr_ego_pose_container->Insert(localization);
ADEBUG << "Received a localization message ["
<< localization.ShortDebugString() << "].";
}
void MessageProcess::OnPlanning(ContainerManager* container_manager,
const planning::ADCTrajectory& adc_trajectory) {
auto ptr_ego_trajectory_container =
container_manager->GetContainer<ADCTrajectoryContainer>(
AdapterConfig::PLANNING_TRAJECTORY);
ACHECK(ptr_ego_trajectory_container != nullptr);
ptr_ego_trajectory_container->Insert(adc_trajectory);
ADEBUG << "Received a planning message [" << adc_trajectory.ShortDebugString()
<< "].";
auto ptr_storytelling_container =
container_manager->GetContainer<StoryTellingContainer>(
AdapterConfig::STORYTELLING);
CHECK_NOTNULL(ptr_storytelling_container);
ptr_ego_trajectory_container->SetJunction(
ptr_storytelling_container->ADCJunctionId(),
ptr_storytelling_container->ADCDistanceToJunction());
}
void MessageProcess::OnStoryTelling(ContainerManager* container_manager,
const Stories& story) {
auto ptr_storytelling_container =
container_manager->GetContainer<StoryTellingContainer>(
AdapterConfig::STORYTELLING);
CHECK_NOTNULL(ptr_storytelling_container);
ptr_storytelling_container->Insert(story);
ADEBUG << "Received a storytelling message [" << story.ShortDebugString()
<< "].";
}
```
OnPerceptionh函数是在收到perception模块数据之后开始上述四个过程对消息进行处理。获得最终的障碍物预测信息。
```message_process.cc
void MessageProcess::OnPerception(
const perception::PerceptionObstacles& perception_obstacles,
const std::shared_ptr<ContainerManager>& container_manager,
EvaluatorManager* evaluator_manager, PredictorManager* predictor_manager,
ScenarioManager* scenario_manager,
PredictionObstacles* const prediction_obstacles) {
// 1. 分析场景和处理容器中的数据
ContainerProcess(container_manager, perception_obstacles, scenario_manager);
auto ptr_obstacles_container =
container_manager->GetContainer<ObstaclesContainer>(
AdapterConfig::PERCEPTION_OBSTACLES);
CHECK_NOTNULL(ptr_obstacles_container);
auto ptr_ego_trajectory_container =
container_manager->GetContainer<ADCTrajectoryContainer>(
AdapterConfig::PLANNING_TRAJECTORY);
CHECK_NOTNULL(ptr_ego_trajectory_container);
// Insert features to FeatureOutput for offline_mode
if (FLAGS_prediction_offline_mode == PredictionConstants::kDumpFeatureProto) {
for (const int id :
ptr_obstacles_container->curr_frame_movable_obstacle_ids()) {
Obstacle* obstacle_ptr = ptr_obstacles_container->GetObstacle(id);
if (obstacle_ptr == nullptr) {
AERROR << "Null obstacle found.";
continue;
}
if (!obstacle_ptr->latest_feature().IsInitialized()) {
AERROR << "Obstacle [" << id << "] has no latest feature.";
continue;
}
// TODO(all): the adc trajectory should be part of features for learning
// algorithms rather than part of the feature.proto
/*
*obstacle_ptr->mutable_latest_feature()->mutable_adc_trajectory_point() =
ptr_ego_trajectory_container->adc_trajectory().trajectory_point();
*/
FeatureOutput::InsertFeatureProto(obstacle_ptr->latest_feature());
ADEBUG << "Insert feature into feature output";
}
// Not doing evaluation on offline mode
return;
}
// 2、进行评估流程
evaluator_manager->Run(ptr_obstacles_container);
if (FLAGS_prediction_offline_mode ==
PredictionConstants::kDumpDataForLearning ||
FLAGS_prediction_offline_mode == PredictionConstants::kDumpFrameEnv) {
return;
}
// 3、进行预测流程
predictor_manager->Run(perception_obstacles, ptr_ego_trajectory_container,
ptr_obstacles_container);
// 输出障碍物的预测信息
*prediction_obstacles = predictor_manager->prediction_obstacles();
}
```
## planning
### PlanningComponent
输入:
/apollo/prediction
/apollo/canbus/chassis
/apollo/localization/pose
/apollo/routing_response
/apollo/perception/traffic_light
/apollo/planning/pad
/apollo/storytelling
/apollo/relative_map(设置了导航模式时需要读取)
输出:
/apollo/planning
/apollo/routing_request
/apollo/planning/learning_data
模块入口时PlanningComponent的Init函数,在其中会根据配置选择不同的planning实现方式:
NaviPlanning:导航模式下使用相对地图的自动驾驶(navi_planning.h/navi_planning.cc)
OnLanePlanning:主要的应用场景是开放道路的自动驾驶(on_lane_planning.h/on_lane_planning.cc)
```planning_component.cc
bool PlanningComponent::Init() {
injector_ = std::make_shared<DependencyInjector>();
if (FLAGS_use_navigation_mode) {
planning_base_ = std::make_unique<NaviPlanning>(injector_);
} else {
planning_base_ = std::make_unique<OnLanePlanning>(injector_);
}
ACHECK(ComponentBase::GetProtoConfig(&config_))
<< "failed to load planning config file "
<< ComponentBase::ConfigFilePath();
if (FLAGS_planning_offline_learning ||
config_.learning_mode() != PlanningConfig::NO_LEARNING) {
if (!message_process_.Init(config_, injector_)) {
AERROR << "failed to init MessageProcess";
return false;
}
}
planning_base_->Init(config_);
routing_reader_ = node_->CreateReader<RoutingResponse>(
config_.topic_config().routing_response_topic(),
[this](const std::shared_ptr<RoutingResponse>& routing) {
AINFO << "Received routing data: run routing callback."
<< routing->header().DebugString();
std::lock_guard<std::mutex> lock(mutex_);
routing_.CopyFrom(*routing);
});
traffic_light_reader_ = node_->CreateReader<TrafficLightDetection>(
config_.topic_config().traffic_light_detection_topic(),
[this](const std::shared_ptr<TrafficLightDetection>& traffic_light) {
ADEBUG << "Received traffic light data: run traffic light callback.";
std::lock_guard<std::mutex> lock(mutex_);
traffic_light_.CopyFrom(*traffic_light);
});
pad_msg_reader_ = node_->CreateReader<PadMessage>(
config_.topic_config().planning_pad_topic(),
[this](const std::shared_ptr<PadMessage>& pad_msg) {
ADEBUG << "Received pad data: run pad callback.";
std::lock_guard<std::mutex> lock(mutex_);
pad_msg_.CopyFrom(*pad_msg);
});
story_telling_reader_ = node_->CreateReader<Stories>(
config_.topic_config().story_telling_topic(),
[this](const std::shared_ptr<Stories>& stories) {
ADEBUG << "Received story_telling data: run story_telling callback.";
std::lock_guard<std::mutex> lock(mutex_);
stories_.CopyFrom(*stories);
});
if (FLAGS_use_navigation_mode) {
relative_map_reader_ = node_->CreateReader<MapMsg>(
config_.topic_config().relative_map_topic(),
[this](const std::shared_ptr<MapMsg>& map_message) {
ADEBUG << "Received relative map data: run relative map callback.";
std::lock_guard<std::mutex> lock(mutex_);
relative_map_.CopyFrom(*map_message);
});
}
planning_writer_ = node_->CreateWriter<ADCTrajectory>(
config_.topic_config().planning_trajectory_topic());
rerouting_writer_ = node_->CreateWriter<RoutingRequest>(
config_.topic_config().routing_request_topic());
planning_learning_data_writer_ = node_->CreateWriter<PlanningLearningData>(
config_.topic_config().planning_learning_data_topic());
return true;
}
```
PlanningComponent的Proc函数对输入的数据进行处理,生成规划线路并发布轨迹信息。
```
bool PlanningComponent::Proc(...) {
// 1. 检查是否需要重新规划线路。
/// 如果需要重新规划路线则使用rerouting_writer_向routing模块发送routing request
CheckRerouting();
// 2. 数据放入local_view_中,并且检查输入数据。
...
// 3. 执行注册好的Planning,生成线路。
planning_base_->RunOnce(local_view_, &adc_trajectory_pb);
// 4. 发布消息
planning_writer_->Write(std::make_shared<ADCTrajectory>(adc_trajectory_pb));
}
```
## routing
主要关注起点到终点的长期路径,根据起点到终点之间的道路,选择一条最优路径。
### RoutingComponent
输入:
/apollo/routing_request(由planning模块发起routing请求)
地图数据
输出:
/apollo/routing_response
## storytelling
根据一些预定义的规则,该模块创建一个或多个story并发布到/apollo/storytling频道。
本模块的主要优点是微调驾驶体验,并将复杂的场景分离出来,将它们打包成故事,供其他模块(如规划、控制等)订阅。
输入:
hd map
/apollo/planning(planning模块生成的轨迹信息)
输出:
/apollo/storytling
### storytelling源码分析
storytelling.cc
```storytelling.cc
bool Storytelling::Init() {
//创建frame_manager_
frame_manager_ = std::make_shared<FrameManager>(node_);
//创建CloseToJunctionTeller
story_tellers_.emplace_back(new CloseToJunctionTeller(frame_manager_));
//获取模块配置信息
if (!cyber::ComponentBase::GetProtoConfig(&config_)) {
AERROR << "Unable to load storytelling conf file: "
<< cyber::ComponentBase::ConfigFilePath();
return false;
}
//创建消息发布者
story_writer_ =
node_->CreateWriter<Stories>(config_.topic_config().storytelling_topic());
// 初始化所有 story_tellers
for (const auto& teller : story_tellers_) {
teller->Init(config_);
}
return true;
}
bool Storytelling::Proc() {
//调用StartFrame函数,接收数据
frame_manager_->StartFrame();
//调用update函数更新story信息
// Query all tellers.
for (const auto& teller : story_tellers_) {
teller->Update(&stories_);
}
//发布新的story信息
// Send stories.
apollo::common::util::FillHeader("Storytelling", &stories_);
story_writer_->Write(stories_);
frame_manager_->EndFrame();
return true;
}
```
从上述代码中可以主要的逻辑是通过frame_manager_和CloseToJunctionTeller中的函数实现。
frame_manager.cc
```frame_manager.cc
FrameManager::FrameManager(const std::shared_ptr<cyber::Node>& node)
: log_buffer_(apollo::common::monitor::MonitorMessageItem::STORYTELLING),
node_(node) {}
//node_->Observe接收数据
void FrameManager::StartFrame() { node_->Observe(); }
void FrameManager::EndFrame() {
// Print and publish all monitor logs.
log_buffer_.Publish();
}
```
close_to_junction_teller.cc重要的逻辑在Update中实现,首先会获取planning模块的预测轨迹信息,然后调用GetOverlaps函数从中读取overlap数据来判断即将遇到的场景(CloseToClearArea、CloseToCrosswalk、CloseToJunction、CloseToSignal、CloseToStopSign、CloseToYieldSign等)。
```close_to_junction_teller.cc
void CloseToJunctionTeller::Update(Stories* stories) {
static auto planning_reader =
frame_manager_->CreateOrGetReader<ADCTrajectory>(
config_.topic_config().planning_trajectory_topic());
const auto trajectory = planning_reader->GetLatestObserved();
if (trajectory == nullptr || trajectory->trajectory_point().empty()) {
AERROR << "Planning trajectory not ready.";
return;
}
GetOverlaps(*trajectory);
// CloseToClearArea
if (!clear_area_id_.empty() && clear_area_distance_ >= 0) {
if (!stories->has_close_to_clear_area()) {
AINFO << "Enter CloseToClearArea story";
}
auto* story = stories->mutable_close_to_clear_area();
story->set_id(clear_area_id_);
story->set_distance(clear_area_distance_);
} else if (stories->has_close_to_clear_area()) {
AINFO << "Exit CloseToClearArea story";
stories->clear_close_to_clear_area();
}
// CloseToCrosswalk
if (!crosswalk_id_.empty() && crosswalk_distance_ >= 0) {
if (!stories->has_close_to_crosswalk()) {
AINFO << "Enter CloseToCrosswalk story";
}
auto* story = stories->mutable_close_to_crosswalk();
story->set_id(crosswalk_id_);
story->set_distance(crosswalk_distance_);
} else if (stories->has_close_to_crosswalk()) {
AINFO << "Exit CloseToCrosswalk story";
stories->clear_close_to_crosswalk();
}
// CloseToJunction
if ((!junction_id_.empty() && junction_distance_ >= 0) ||
(!pnc_junction_id_.empty() && pnc_junction_distance_ >= 0)) {
if (!stories->has_close_to_junction()) {
AINFO << "Enter CloseToJunction story";
}
auto* story = stories->mutable_close_to_junction();
if (!pnc_junction_id_.empty() && pnc_junction_distance_ >= 0) {
story->set_id(pnc_junction_id_);
story->set_type(CloseToJunction::PNC_JUNCTION);
story->set_distance(pnc_junction_distance_);
} else {
story->set_id(junction_id_);
story->set_type(CloseToJunction::JUNCTION);
story->set_distance(junction_distance_);
}
} else if (stories->has_close_to_junction()) {
AINFO << "Exit CloseToJunction story";
stories->clear_close_to_junction();
}
// CloseToSignal
if (!signal_id_.empty() && signal_distance_ >= 0) {
if (!stories->has_close_to_signal()) {
AINFO << "Enter CloseToSignal story";
}
auto* story = stories->mutable_close_to_signal();
story->set_id(signal_id_);
story->set_distance(signal_distance_);
} else if (stories->has_close_to_signal()) {
AINFO << "Exit CloseToSignal story";
stories->clear_close_to_signal();
}
// CloseToStopSign
if (!stop_sign_id_.empty() && stop_sign_distance_ >= 0) {
if (!stories->has_close_to_stop_sign()) {
AINFO << "Enter CloseToStopSign story";
}
auto* story = stories->mutable_close_to_stop_sign();
story->set_id(stop_sign_id_);
story->set_distance(stop_sign_distance_);
} else if (stories->has_close_to_stop_sign()) {
AINFO << "Exit CloseToStopSign story";
stories->clear_close_to_stop_sign();
}
// CloseToYieldSign
if (!yield_sign_id_.empty() && yield_sign_distance_ >= 0) {
if (!stories->has_close_to_yield_sign()) {
AINFO << "Enter CloseToYieldSign story";
}
auto* story = stories->mutable_close_to_yield_sign();
story->set_id(yield_sign_id_);
story->set_distance(yield_sign_distance_);
} else if (stories->has_close_to_yield_sign()) {
AINFO << "Exit CloseToYieldSign story";
stories->clear_close_to_yield_sign();
}
}
```
其中在GetOverlaps函数中还会调用一堆Get函数就是用来获取不同场景的数据,判断有哪些场景即将出现并创建对应的story压入stories数据结构中
```close_to_junction_teller.cc
void CloseToJunctionTeller::GetOverlaps(const ADCTrajectory& adc_trajectory) {
static std::string overlapping_junction_id;
const double s_start = adc_trajectory.trajectory_point(0).path_point().s();
clear_area_id_.clear();
clear_area_distance_ = -1;
crosswalk_id_.clear();
crosswalk_distance_ = -1;
junction_id_.clear();
junction_distance_ = -1;
pnc_junction_id_.clear();
pnc_junction_distance_ = -1;
signal_id_.clear();
signal_distance_ = -1;
stop_sign_id_.clear();
stop_sign_distance_ = -1;
yield_sign_id_.clear();
yield_sign_distance_ = -1;
for (const auto& point : adc_trajectory.trajectory_point()) {
const auto& path_point = point.path_point();
if (path_point.s() > FLAGS_adc_trajectory_search_distance) {
break;
}
// clear_area
if (clear_area_id_.empty() || clear_area_distance_ < 0) {
std::string clear_area_id;
if (GetClearArea(path_point, &clear_area_id)) {
clear_area_id_ = clear_area_id;
clear_area_distance_ = path_point.s() - s_start;
}
}
// crosswalk
if (crosswalk_id_.empty() || crosswalk_distance_ < 0) {
std::string crosswalk_id;
if (GetCrosswalk(path_point, &crosswalk_id)) {
crosswalk_id_ = crosswalk_id;
crosswalk_distance_ = path_point.s() - s_start;
}
}
// junction
if (junction_id_.empty() || junction_distance_ < 0) {
std::string junction_id;
if (GetJunction(path_point, &junction_id)) {
junction_id_ = junction_id;
junction_distance_ = path_point.s() - s_start;
}
}
// pnc_junction
if (pnc_junction_id_.empty() || pnc_junction_distance_ < 0) {
std::string pnc_junction_id;
if (GetPNCJunction(path_point, &pnc_junction_id)) {
pnc_junction_id_ = pnc_junction_id;
pnc_junction_distance_ = path_point.s() - s_start;
}
}
// signal
if (signal_id_.empty() || signal_distance_ < 0) {
std::string signal_id;
if (GetSignal(path_point, &signal_id)) {
signal_id_ = signal_id;
signal_distance_ = path_point.s() - s_start;
}
}
// stop_sign
if (stop_sign_id_.empty() || stop_sign_distance_ < 0) {
std::string stop_sign_id;
if (GetStopSign(path_point, &stop_sign_id)) {
stop_sign_id_ = stop_sign_id;
stop_sign_distance_ = path_point.s() - s_start;
}
}
// yield_sign
if (yield_sign_id_.empty() || yield_sign_distance_ < 0) {
std::string yield_sign_id;
if (GetYieldSign(path_point, &yield_sign_id)) {
yield_sign_id_ = yield_sign_id;
yield_sign_distance_ = path_point.s() - s_start;
}
}
}
}
void CloseToJunctionTeller::Init(const StorytellingConfig& storytelling_conf) {
config_.CopyFrom(storytelling_conf);
frame_manager_->CreateOrGetReader<ADCTrajectory>(
config_.topic_config().planning_trajectory_topic());
}
```
## transform
进行坐标变换
### StaticTransformComponent
输入:
传感器外参标定结果(使用yaml文件存储)
输出:
/tf_static
### yaml文件举例
对于标定结果的描述,常用刚体变换中的旋转变换和平移变换来表示,其中涉及到child_frame_id表示该传感器数据所在的坐标系,frame_id则表示该标定结果描述了从child_frame_id到frame_id的变换关系。
```
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: velodyne128
child_frame_id: front_6mm
transform:
translation:
x: 0.580393
y: 0.0727572
z: -0.211861
rotation:
x: -0.502988
y: 0.496432
z: -0.507426
w: 0.493029
euler_angles_degree:
pitch: -89.936
yaw: -90.45
roll: -1.20027
```
### 源码分析
```static_transform_component.cc
bool StaticTransformComponent::Init() {
//读取配置文件
if (!GetProtoConfig(&conf_)) {
AERROR << "Parse conf file failed, " << ConfigFilePath();
return false;
}
//发布消息
cyber::proto::RoleAttributes attr;
attr.set_channel_name(FLAGS_tf_static_topic);
attr.mutable_qos_profile()->CopyFrom(
cyber::transport::QosProfileConf::QOS_PROFILE_TF_STATIC);
writer_ = node_->CreateWriter<TransformStampeds>(attr);
SendTransforms();
return true;
}
```
```static_transform_component.cc
void StaticTransformComponent::SendTransforms() {
std::vector<TransformStamped> tranform_stamped_vec;
//遍历所有yaml文件
for (auto& extrinsic_file : conf_.extrinsic_file()) {
if (extrinsic_file.enable()) {
AINFO << "Broadcast static transform, frame id ["
<< extrinsic_file.frame_id() << "], child frame id ["
<< extrinsic_file.child_frame_id() << "]";
TransformStamped transform;
//调用ParseFromYaml解析yaml文件中的转换关系压入队列
if (ParseFromYaml(extrinsic_file.file_path(), &transform)) {
tranform_stamped_vec.emplace_back(transform);
}
}
}
//调用SendTransform发布这些坐标系转化关系
SendTransform(tranform_stamped_vec);
}
```
## monitor
监控系统的软硬件运行状态信息
### monitor.dag
```monitor.dag
module_config {
module_library : "/apollo/bazel-bin/modules/monitor/libmonitor.so"
//定时模块配置信息
timer_components {
class_name : "Monitor"
config {
name: "monitor"
//定时任务时间间隔为500 ms
interval: 500
}
}
}
```
### 源码分析
Init函数中初始化一堆Monitor用来监控不同模块、不同软件、不同硬件的信息
所有Monitor都继承RecurrentRunner类
```monitor.cc
bool Monitor::Init() {
MonitorManager::Instance()->Init(node_);
// Only the one CAN card corresponding to current mode will take effect.
runners_.emplace_back(new EsdCanMonitor());
runners_.emplace_back(new SocketCanMonitor());
// To enable the GpsMonitor, you must add FLAGS_gps_component_name to the
// mode's monitored_components.
runners_.emplace_back(new GpsMonitor());
// To enable the LocalizationMonitor, you must add
// FLAGS_localization_component_name to the mode's monitored_components.
runners_.emplace_back(new LocalizationMonitor());
// To enable the CameraMonitor, you must add
// FLAGS_camera_component_name to the mode's monitored_components.
runners_.emplace_back(new CameraMonitor());
// Monitor if processes are running.
runners_.emplace_back(new ProcessMonitor());
// Monitor if modules are running.
runners_.emplace_back(new ModuleMonitor());
// Monitor message processing latencies across modules
const std::shared_ptr<LatencyMonitor> latency_monitor(new LatencyMonitor());
runners_.emplace_back(latency_monitor);
// Monitor if channel messages are updated in time.
runners_.emplace_back(new ChannelMonitor(latency_monitor));
// Monitor if resources are sufficient.
runners_.emplace_back(new ResourceMonitor());
// Monitor all changes made by each sub-monitor, and summarize to a final
// overall status.
runners_.emplace_back(new SummaryMonitor());
// Check functional safety according to the summary.
if (FLAGS_enable_functional_safety) {
runners_.emplace_back(new FunctionalSafetyMonitor());
}
return true;
}
bool Monitor::Proc() {
const double current_time = apollo::cyber::Clock::NowInSeconds();
if (!MonitorManager::Instance()->StartFrame(current_time)) {
return false;
}
//对每个需要监控的Monitor调用Tick函数
for (auto& runner : runners_) {
runner->Tick(current_time);
}
MonitorManager::Instance()->EndFrame();
return true;
}
```
在RecurrentRunner类中Tick函数会判断当前执行时间是否距离上次执行时间超过interval_
如果是执行RunOnce函数获取状态信息并更新next_round
```
void RecurrentRunner::Tick(const double current_time) {
if (next_round_ <= current_time) {
++round_count_;
AINFO_EVERY(100) << name_ << " is running round #" << round_count_;
next_round_ = current_time + interval_;
RunOnce(current_time);
}
}
```
值得注意的是Monitor继承的是TimeComponent,这种类型的component初始化时会根据配置文件中的interval(单位:ms)配置定时任务。
主要流程:
1、创建Node
2、调用用户自定义初始化函数
3、创建定时器,定时调用"Proc()"函数
```cyber/component/timer_component.cc
bool TimerComponent::Initialize(const TimerComponentConfig& config) {
if (!config.has_name() || !config.has_interval()) {
AERROR << "Missing required field in config file.";
return false;
}
// 1、创建Node
node_.reset(new Node(config.name()));
LoadConfigFiles(config);
// 2、调用用户自定义初始化函数
if (!Init()) {
return false;
}
// 3、创建定时器,定时调用"Proc()"函数
std::shared_ptr<TimerComponent> self =
std::dynamic_pointer_cast<TimerComponent>(shared_from_this());
auto func = [self]() { self->Proc(); };
timer_.reset(new Timer(config.interval(), func, false));
timer_->Start();
return true;
}
```
## guardian
### GuardianComponent
输入:
/apollo/canbus/chassis
/apollo/control
/apollo/monitor/system_status
输出:
/apollo/guardian
### 源码分析
```
bool GuardianComponent::Init() {
if (!GetProtoConfig(&guardian_conf_)) {
AERROR << "Unable to load canbus conf file: " << ConfigFilePath();
return false;
}
//初始化readers读取所需的数据
////读取车辆底盘状态信息
chassis_reader_ = node_->CreateReader<Chassis>(
FLAGS_chassis_topic, [this](const std::shared_ptr<Chassis>& chassis) {
ADEBUG << "Received chassis data: run chassis callback.";
std::lock_guard<std::mutex> lock(mutex_);
chassis_.CopyFrom(*chassis);
});
////读取control模块的command命令
control_cmd_reader_ = node_->CreateReader<ControlCommand>(
FLAGS_control_command_topic,
[this](const std::shared_ptr<ControlCommand>& cmd) {
ADEBUG << "Received control data: run control callback.";
std::lock_guard<std::mutex> lock(mutex_);
control_cmd_.CopyFrom(*cmd);
});
////读取monitor中获取的系统状态信息
system_status_reader_ = node_->CreateReader<SystemStatus>(
FLAGS_system_status_topic,
[this](const std::shared_ptr<SystemStatus>& status) {
ADEBUG << "Received system status data: run system status callback.";
std::lock_guard<std::mutex> lock(mutex_);
last_status_received_s_ = Time::Now().ToSecond();
system_status_.CopyFrom(*status);
});
//创建消息的发布者
guardian_writer_ = node_->CreateWriter<GuardianCommand>(FLAGS_guardian_topic);
return true;
}
bool GuardianComponent::Proc() {
constexpr double kSecondsTillTimeout(2.5);
//判断是是否需要启动安全模式
bool safety_mode_triggered = false;
if (guardian_conf_.guardian_enable()) {
std::lock_guard<std::mutex> lock(mutex_);
if (Time::Now().ToSecond() - last_status_received_s_ >
kSecondsTillTimeout) {
safety_mode_triggered = true;
}
safety_mode_triggered =
safety_mode_triggered || system_status_.has_safety_mode_trigger_time();
}
if (safety_mode_triggered) {
//启动安全模式
ADEBUG << "Safety mode triggered, enable safety mode";
TriggerSafetyMode();
} else {
ADEBUG << "Safety mode not triggered, bypass control command";
//直接将control模块的命令封装并传递
PassThroughControlCommand();
}
//发布guardian模块的command
common::util::FillHeader(node_->Name(), &guardian_cmd_);
guardian_writer_->Write(guardian_cmd_);
return true;
}
```
PassThroughControlCommand函数是直接将control模块传递过来的command命令封装到guardian_cmd_命令中。
TriggerSafetyMode函数则需要在guardian_cmd_加入额外的命令来启动安全模式控制车辆刹车等。
### guardian.dag
GuardianComponent也是一个TimerComponent,定时任务的时间间隔为10ms
```
module_config {
module_library : "/apollo/bazel-bin/modules/guardian/libguardian_component.so",
timer_components {
class_name : "GuardianComponent"
config {
name: "guardian"
config_file_path: "/apollo/modules/guardian/conf/guardian_conf.pb.txt"
interval: 10
}
}
}
```
## control
### control.dag
ControlComponent也是一个TimerComponent,定时任务的时间间隔为10ms
```control.dag
module_config {
module_library : "/apollo/bazel-bin/modules/control/libcontrol_component.so"
timer_components {
class_name : "ControlComponent"
config {
name: "control"
flag_file_path: "/apollo/modules/control/conf/control.conf"
interval: 10
}
}
}
```
### mpc_module.dag
```mpc_module.dag
module_config {
module_library : "/apollo/bazel-bin/modules/control/libcontrol_component.so"
timer_components {
class_name : "ControlComponent"
config {
name: "control"
flag_file_path: "/apollo/modules/control/conf/control.conf"
interval: 10
}
}
components {
class_name : "PreprocessorSubmodule"
config {
name: "PreprocessorSubmodule"
config_file_path: "/apollo/modules/control/conf/control_common_conf.pb.txt"
flag_file_path: "/apollo/modules/control/conf/control.conf"
readers: [
{
channel:"/apollo/control/localview"
}
]
}
}
components {
class_name : "MPCControllerSubmodule"
config {
name: "MPCControllerSubmodule"
flag_file_path: "/apollo/modules/control/conf/control.conf"
readers: [
{
channel:"/apollo/control/preprocessor"
}
]
}
}
components {
class_name : "PostprocessorSubmodule"
config {
name: "PostprocessorSubmodule"
config_file_path: "/apollo/modules/control/conf/control_common_conf.pb.txt"
flag_file_path: "/apollo/modules/control/conf/control.conf"
readers: [
{
channel:"/apollo/control/controlcore"
}
]
}
}
}
```
### lateral_longitudinal_module.dag
```lateral_longitudinal_module.dag
module_config {
module_library : "/apollo/bazel-bin/modules/control/libcontrol_component.so"
timer_components {
class_name : "ControlComponent"
config {
name: "control"
flag_file_path: "/apollo/modules/control/conf/control.conf"
interval: 10
}
}
components {
class_name : "PreprocessorSubmodule"
config {
name: "PreprocessorSubmodule"
config_file_path: "/apollo/modules/control/conf/control_common_conf.pb.txt"
flag_file_path: "/apollo/modules/control/conf/control.conf"
readers: [
{
channel:"/apollo/control/localview"
}
]
}
}
components {
class_name : "LatLonControllerSubmodule"
config {
name: "LatLonControllerSubmodule"
config_file_path: "/apollo/modules/control/conf/control_common_conf.pb.txt"
flag_file_path: "/apollo/modules/control/conf/control.conf"
readers: [
{
channel:"/apollo/control/preprocessor"
}
]
}
}
components {
class_name : "PostprocessorSubmodule"
config {
name: "PostprocessorSubmodule"
config_file_path: "/apollo/modules/control/conf/control_common_conf.pb.txt"
flag_file_path: "/apollo/modules/control/conf/control.conf"
readers: [
{
channel:"/apollo/control/controlcore"
}
]
}
}
}
```
### ControlComponent
输入:
/apollo/canbus/chassis
/apollo/planning
/apollo/localization/pose
/apollo/control/pad
输出:
/apollo/control
/apollo/control/localview(启用了submodules处理数据)
### PreprocessorSubmodule
输入:
/apollo/control/localview
输出:
/apollo/control/preprocessor
### MPCControllerSubmodule
输入:
/apollo/control/preprocessor
输出:
/apollo/control/controlcore
### LatLonControllerSubmodule
输入:
/apollo/control/preprocessor
输出:
/apollo/control/controlcore
### PostprocessorSubmodule
输入:
/apollo/control/controlcore
输出:
/apollo/control
### 源码分析
#### ControlComponent::Init
ControlComponent的Init中会注册读取数据的readers并根据是否启用子模块来判断应该创建哪一个channel的writer发布数据
```ControlComponent::Init
bool ControlComponent::Init() {
injector_ = std::make_shared<DependencyInjector>();
init_time_ = Clock::Now();
AINFO << "Control init, starting ...";
ACHECK(
//读取配置文件 cyber::common::GetProtoFromFile(FLAGS_control_conf_file, &control_conf_))
<< "Unable to load control conf file: " + FLAGS_control_conf_file;
AINFO << "Conf file: " << FLAGS_control_conf_file << " is loaded.";
AINFO << "Conf file: " << ConfigFilePath() << " is loaded.";
// initial controller agent when not using control submodules
ADEBUG << "FLAGS_use_control_submodules: " << FLAGS_use_control_submodules;
//判断是否启用子模块,没有的话根据配置文件初始化controller_agent_
if (!FLAGS_use_control_submodules &&
!controller_agent_.Init(injector_, &control_conf_).ok()) {
// set controller
ADEBUG << "original control";
monitor_logger_buffer_.ERROR("Control init controller failed! Stopping...");
return false;
}
//读取车辆底盘信息
cyber::ReaderConfig chassis_reader_config;
chassis_reader_config.channel_name = FLAGS_chassis_topic;
chassis_reader_config.pending_queue_size = FLAGS_chassis_pending_queue_size;
chassis_reader_ =
node_->CreateReader<Chassis>(chassis_reader_config, nullptr);
ACHECK(chassis_reader_ != nullptr);
//读取planning模块规划的轨迹信息
cyber::ReaderConfig planning_reader_config;
planning_reader_config.channel_name = FLAGS_planning_trajectory_topic;
planning_reader_config.pending_queue_size = FLAGS_planning_pending_queue_size;
trajectory_reader_ =
node_->CreateReader<ADCTrajectory>(planning_reader_config, nullptr);
ACHECK(trajectory_reader_ != nullptr);
//读取定位模块的位置信息
cyber::ReaderConfig localization_reader_config;
localization_reader_config.channel_name = FLAGS_localization_topic;
localization_reader_config.pending_queue_size =
FLAGS_localization_pending_queue_size;
localization_reader_ = node_->CreateReader<LocalizationEstimate>(
localization_reader_config, nullptr);
ACHECK(localization_reader_ != nullptr);
//来自人机交互模块的请求信息
cyber::ReaderConfig pad_msg_reader_config;
pad_msg_reader_config.channel_name = FLAGS_pad_topic;
pad_msg_reader_config.pending_queue_size = FLAGS_pad_msg_pending_queue_size;
pad_msg_reader_ =
node_->CreateReader<PadMessage>(pad_msg_reader_config, nullptr);
ACHECK(pad_msg_reader_ != nullptr);
//如果没有启用子模块则直接在当前模块输出控制指令
if (!FLAGS_use_control_submodules) {
control_cmd_writer_ =
node_->CreateWriter<ControlCommand>(FLAGS_control_command_topic);
ACHECK(control_cmd_writer_ != nullptr);
} else {
//若启用了子模块则将处理的数据通过local_view_writer_发布给子模块处理
local_view_writer_ =
node_->CreateWriter<LocalView>(FLAGS_control_local_view_topic);
ACHECK(local_view_writer_ != nullptr);
}
// set initial vehicle state by cmd
// need to sleep, because advertised channel is not ready immediately
// simple test shows a short delay of 80 ms or so
AINFO << "Control resetting vehicle state, sleeping for 1000 ms ...";
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
// should init_vehicle first, let car enter work status, then use status msg
// trigger control
AINFO << "Control default driving action is "
<< DrivingAction_Name(control_conf_.action());
pad_msg_.set_action(control_conf_.action());
return true;
}
```
#### ControlComponent::Proc
Proc函数中会调用每个reader的Observe函数来接收结束并调用对应的函数处理接收到的数据。
```control_component.h
// Upon receiving pad message
void OnPad(const std::shared_ptr<PadMessage> &pad);
void OnChassis(const std::shared_ptr<apollo::canbus::Chassis> &chassis);
void OnPlanning(
const std::shared_ptr<apollo::planning::ADCTrajectory> &trajectory);
void OnLocalization(
const std::shared_ptr<apollo::localization::LocalizationEstimate>
&localization);
// Upon receiving monitor message
void OnMonitor(
const apollo::common::monitor::MonitorMessage &monitor_message);
```
而后会根据会根据是否启用子模块判断继续处理数据还是将数据通过local_view_writer_发布给子模块处理后返回
```
// use control submodules
if (FLAGS_use_control_submodules) {
local_view_.mutable_header()->set_lidar_timestamp(
local_view_.trajectory().header().lidar_timestamp());
local_view_.mutable_header()->set_camera_timestamp(
local_view_.trajectory().header().camera_timestamp());
local_view_.mutable_header()->set_radar_timestamp(
local_view_.trajectory().header().radar_timestamp());
common::util::FillHeader(FLAGS_control_local_view_topic, &local_view_);
const auto end_time = Clock::Now();
// measure latency
static apollo::common::LatencyRecorder latency_recorder(
FLAGS_control_local_view_topic);
latency_recorder.AppendLatencyRecord(
local_view_.trajectory().header().lidar_timestamp(), start_time,
end_time);
local_view_writer_->Write(local_view_);
return true;
}
```
如果没有启用子模块直接处理数据会调用ProduceControlCommand函数来生成控制指令最后通过control_cmd_writer_发布。
```
ControlCommand control_command;
Status status = ProduceControlCommand(&control_command);
AERROR_IF(!status.ok()) << "Failed to produce control command:"
<< status.error_message();
if (pad_received_) {
control_command.mutable_pad_msg()->CopyFrom(pad_msg_);
pad_received_ = false;
}
// forward estop reason among following control frames.
if (estop_) {
control_command.mutable_header()->mutable_status()->set_msg(estop_reason_);
}
// set header
control_command.mutable_header()->set_lidar_timestamp(
local_view_.trajectory().header().lidar_timestamp());
control_command.mutable_header()->set_camera_timestamp(
local_view_.trajectory().header().camera_timestamp());
control_command.mutable_header()->set_radar_timestamp(
local_view_.trajectory().header().radar_timestamp());
common::util::FillHeader(node_->Name(), &control_command);
ADEBUG << control_command.ShortDebugString();
if (control_conf_.is_control_test_mode()) {
ADEBUG << "Skip publish control command in test mode";
return true;
}
const auto end_time = Clock::Now();
const double time_diff_ms = (end_time - start_time).ToSecond() * 1e3;
ADEBUG << "total control time spend: " << time_diff_ms << " ms.";
control_command.mutable_latency_stats()->set_total_time_ms(time_diff_ms);
control_command.mutable_latency_stats()->set_total_time_exceeded(
time_diff_ms > control_conf_.control_period() * 1e3);
ADEBUG << "control cycle time is: " << time_diff_ms << " ms.";
status.Save(control_command.mutable_header()->mutable_status());
// measure latency
if (local_view_.trajectory().header().has_lidar_timestamp()) {
static apollo::common::LatencyRecorder latency_recorder(
FLAGS_control_command_topic);
latency_recorder.AppendLatencyRecord(
local_view_.trajectory().header().lidar_timestamp(), start_time,
end_time);
}
control_cmd_writer_->Write(control_command);
return true;
```
#### ControlComponent::ProduceControlCommand
ProduceControlCommand函数主要生成控制指令的操作是通过controller_agent_的ComputeControlCommand函数来完成。
```ControlComponent::ProduceControlCommand
// controller agent
Status status_compute = controller_agent_.ComputeControlCommand(
&local_view_.localization(), &local_view_.chassis(),
&local_view_.trajectory(), control_command);
if (!status_compute.ok()) {
AERROR << "Control main function failed"
<< " with localization: "
<< local_view_.localization().ShortDebugString()
<< " with chassis: " << local_view_.chassis().ShortDebugString()
<< " with trajectory: "
<< local_view_.trajectory().ShortDebugString()
<< " with cmd: " << control_command->ShortDebugString()
<< " status:" << status_compute.error_message();
estop_ = true;
estop_reason_ = status_compute.error_message();
status = status_compute;
}
}
```
#### ControllerAgent::Init
ControllerAgent在ControlComponent初始化时被创建,会根据模块的配置文件来注册Controllers处理数据。
```ControllerAgent::Init
Status ControllerAgent::Init(std::shared_ptr<DependencyInjector> injector,
const ControlConf *control_conf) {
injector_ = injector;
RegisterControllers(control_conf);
ACHECK(InitializeConf(control_conf).ok()) << "Failed to initialize config.";
for (auto &controller : controller_list_) {
if (controller == nullptr) {
return Status(ErrorCode::CONTROL_INIT_ERROR, "Controller is null.");
}
if (!controller->Init(injector, control_conf_).ok()) {
AERROR << "Controller <" << controller->Name() << "> init failed!";
return Status(ErrorCode::CONTROL_INIT_ERROR,
"Failed to init Controller:" + controller->Name());
}
AINFO << "Controller <" << controller->Name() << "> init done!";
}
return Status::OK();
}
```
#### ControllerAgent::RegisterControllers
根据配置文件中的active_controllers来注册对应的控制器
```ControllerAgent::RegisterControllers
void ControllerAgent::RegisterControllers(const ControlConf *control_conf) {
AINFO << "Only support MPC controller or Lat + Lon controllers as of now";
for (auto active_controller : control_conf->active_controllers()) {
switch (active_controller) {
case ControlConf::MPC_CONTROLLER:
controller_factory_.Register(
ControlConf::MPC_CONTROLLER,
[]() -> Controller * { return new MPCController(); });
break;
case ControlConf::LAT_CONTROLLER:
controller_factory_.Register(
ControlConf::LAT_CONTROLLER,
[]() -> Controller * { return new LatController(); });
break;
case ControlConf::LON_CONTROLLER:
controller_factory_.Register(
ControlConf::LON_CONTROLLER,
[]() -> Controller * { return new LonController(); });
break;
default:
AERROR << "Unknown active controller type:" << active_controller;
}
}
}
```
配置文件举例
```control_conf.pb.txt
...
soft_estop_brake: 50.0
active_controllers: LAT_CONTROLLER
active_controllers: LON_CONTROLLER
max_steering_percentage_allowed: 100
minimum_speed_resolution: 0.2
...
```
#### ControllerAgent::InitializeConf
创建active_controllers的实例并使用一个controller_list_来存储
```
Status ControllerAgent::InitializeConf(const ControlConf *control_conf) {
if (!control_conf) {
AERROR << "control_conf is null";
return Status(ErrorCode::CONTROL_INIT_ERROR, "Failed to load config");
}
control_conf_ = control_conf;
for (auto controller_type : control_conf_->active_controllers()) {
auto controller = controller_factory_.CreateObject(
static_cast<ControlConf::ControllerType>(controller_type));
if (controller) {
controller_list_.emplace_back(std::move(controller));
} else {
AERROR << "Controller: " << controller_type << "is not supported";
return Status(ErrorCode::CONTROL_INIT_ERROR,
"Invalid controller type:" + controller_type);
}
}
return Status::OK();
}
```
#### ControllerAgent::ComputeControlCommand
这个函数主要功能就是依次调用controller_list_中每一个controller的ComputeControlCommand函数来生成控制命令
```ControllerAgent::ComputeControlCommand
Status ControllerAgent::ComputeControlCommand(
const localization::LocalizationEstimate *localization,
const canbus::Chassis *chassis, const planning::ADCTrajectory *trajectory,
control::ControlCommand *cmd) {
for (auto &controller : controller_list_) {
ADEBUG << "controller:" << controller->Name() << " processing ...";
double start_timestamp = Clock::NowInSeconds();
controller->ComputeControlCommand(localization, chassis, trajectory, cmd);
double end_timestamp = Clock::NowInSeconds();
const double time_diff_ms = (end_timestamp - start_timestamp) * 1000;
ADEBUG << "controller: " << controller->Name()
<< " calculation time is: " << time_diff_ms << " ms.";
cmd->mutable_latency_stats()->add_controller_time_ms(time_diff_ms);
}
return Status::OK();
}
```
#### controllers
- LonController:纵向控制器
- 纵向控制器,主要是通过油门和刹车控制车的纵向速度
- LatController:横向控制器
- 汽车的横向控制主要是通过控制方向盘的转角来控制汽车行驶的角度
- MPCController
- 模型预测控制(MPC)是一类特殊的控制。它的当前控制动作是在每一个采样瞬间通过求解一个有限时域开环最优控制问题而获得。过程的当前状态作为最优控制问题的初始状态,解得的最优控制序列只实施第一个控制作用。这是它与那些使用预先计算控制律的算法的最大不同。本质上模型预测控制求解一个开环最优控制问题。它的思想与具体的模型无关,但是实现则与模型有关。
#### MPCControllerSubmodule
在这个子模块中主要关注Proc函数和ProduceControlCoreCommand
在Proc函数中首先接收来自预处理模块的处理后的数据(PreprocessorSubmodule),然后会调用ProduceControlCoreCommand函数生成控制指令,而ProduceControlCoreCommand函数则会指定mpc_controller_的ComputeControlCommand来处理数据,最后将生成的控制命令交给PostprocessorSubmodule进行最后的封装发布。
```mpc_controller_submodules.cc
bool MPCControllerSubmodule::Proc(
const std::shared_ptr<Preprocessor>& preprocessor_status) {
const auto start_time = Clock::Now();
ControlCommand control_core_command;
// recording pad msg
if (preprocessor_status->received_pad_msg()) {
control_core_command.mutable_pad_msg()->CopyFrom(
preprocessor_status->local_view().pad_msg());
}
ADEBUG << "MPC controller submodule started ....";
// skip produce control command when estop for MPC controller
StatusPb pre_status = preprocessor_status->header().status();
if (pre_status.error_code() != ErrorCode::OK) {
control_core_command.mutable_header()->mutable_status()->CopyFrom(
pre_status);
AERROR << "Error in preprocessor submodule.";
return false;
}
Status status = ProduceControlCoreCommand(preprocessor_status->local_view(),
&control_core_command);
AERROR_IF(!status.ok()) << "Failed to produce control command:"
<< status.error_message();
control_core_command.mutable_header()->set_lidar_timestamp(
preprocessor_status->header().lidar_timestamp());
control_core_command.mutable_header()->set_camera_timestamp(
preprocessor_status->header().camera_timestamp());
control_core_command.mutable_header()->set_radar_timestamp(
preprocessor_status->header().radar_timestamp());
common::util::FillHeader(Name(), &control_core_command);
const auto end_time = Clock::Now();
static apollo::common::LatencyRecorder latency_recorder(
FLAGS_control_core_command_topic);
latency_recorder.AppendLatencyRecord(
control_core_command.header().lidar_timestamp(), start_time, end_time);
control_core_command.mutable_header()->mutable_status()->set_error_code(
status.code());
control_core_command.mutable_header()->mutable_status()->set_msg(
status.error_message());
control_core_writer_->Write(control_core_command);
return status.ok();
}
Status MPCControllerSubmodule::ProduceControlCoreCommand(
const LocalView& local_view, ControlCommand* control_core_command) {
if (local_view.chassis().driving_mode() == Chassis::COMPLETE_MANUAL) {
mpc_controller_.Reset();
AINFO_EVERY(100) << "Reset Controllers in Manual Mode";
}
Status status = mpc_controller_.ComputeControlCommand(
&local_view.localization(), &local_view.chassis(),
&local_view.trajectory(), control_core_command);
ADEBUG << "MPC controller submodule finished.";
return status;
}
```
#### LatLonControllerSubmodule
这个子模块执行过程上面MPCControllerSubmodule过程类似,只不过在ProduceControlCoreCommand中是指定使用lateral_controller_和longitudinal_controller_来处理数据生成控制命令。
```lat_lon_controller_submodule.cc
bool LatLonControllerSubmodule::Proc(
const std::shared_ptr<Preprocessor>& preprocessor_status) {
const auto start_time = Clock::Now();
ControlCommand control_core_command;
// recording pad msg
if (preprocessor_status->received_pad_msg()) {
control_core_command.mutable_pad_msg()->CopyFrom(
preprocessor_status->local_view().pad_msg());
}
ADEBUG << "Lat+Lon controller submodule started ....";
// skip produce control command when estop for lat+lon controller
StatusPb pre_status = preprocessor_status->header().status();
if (pre_status.error_code() != ErrorCode::OK) {
control_core_command.mutable_header()->mutable_status()->CopyFrom(
pre_status);
AERROR << "Error in preprocessor submodule.";
return false;
}
Status status = ProduceControlCoreCommand(preprocessor_status->local_view(),
&control_core_command);
AERROR_IF(!status.ok()) << "Failed to produce control command:"
<< status.error_message();
control_core_command.mutable_header()->set_lidar_timestamp(
preprocessor_status->header().lidar_timestamp());
control_core_command.mutable_header()->set_camera_timestamp(
preprocessor_status->header().camera_timestamp());
control_core_command.mutable_header()->set_radar_timestamp(
preprocessor_status->header().radar_timestamp());
common::util::FillHeader(Name(), &control_core_command);
const auto end_time = Clock::Now();
static apollo::common::LatencyRecorder latency_recorder(
FLAGS_control_core_command_topic);
latency_recorder.AppendLatencyRecord(
control_core_command.header().lidar_timestamp(), start_time, end_time);
control_core_command.mutable_header()->mutable_status()->set_error_code(
status.code());
control_core_command.mutable_header()->mutable_status()->set_msg(
status.error_message());
control_core_writer_->Write(control_core_command);
return status.ok();
}
Status LatLonControllerSubmodule::ProduceControlCoreCommand(
const LocalView& local_view, ControlCommand* control_core_command) {
std::lock_guard<std::mutex> lock(mutex_);
if (local_view.chassis().driving_mode() == Chassis::COMPLETE_MANUAL) {
lateral_controller_.Reset();
longitudinal_controller_.Reset();
AINFO_EVERY(100) << "Reset Controllers in Manual Mode";
}
// fill out control command sequentially
Status lateral_status = lateral_controller_.ComputeControlCommand(
&local_view.localization(), &local_view.chassis(),
&local_view.trajectory(), control_core_command);
// return error if lateral status has error
if (!lateral_status.ok()) {
return lateral_status;
}
Status longitudinal_status = longitudinal_controller_.ComputeControlCommand(
&local_view.localization(), &local_view.chassis(),
&local_view.trajectory(), control_core_command);
return longitudinal_status;
}
```
## localization
### 定位分类
rtk定位
ndt定位
msf定位
### rtk定位
#### rtk_localization.launch
```
<cyber>
<module>
<name>localization</name>
<dag_conf>/apollo/modules/localization/dag/dag_streaming_rtk_localization.dag</dag_conf>
<process_name>localization</process_name>
</module>
</cyber>
```
#### dag_streaming_rtk_localization.dag
```
# Define all coms in DAG streaming.
module_config {
module_library : "/apollo/bazel-bin/modules/localization/rtk/librtk_localization_component.so"
components {
class_name : "RTKLocalizationComponent"
config {
name : "rtk_localization"
config_file_path : "/apollo/modules/localization/conf/rtk_localization.pb.txt"
readers: [
{
channel: "/apollo/sensor/gnss/odometry"
qos_profile: {
depth : 10
}
pending_queue_size: 50
}
]
}
}
}
```
#### RTKLocalizationComponent
输入:
/apollo/sensor/gnss/odometry
/apollo/sensor/gnss/corrected_imu
/apollo/sensor/gnss/ins_stat
输出:
/apollo/localization/pose
/apollo/localization/msf_status
#### 源码分析
RTKLocalizationComponent 的Init函数中会调用IntiConfig和InitIO来初始化
```Init
bool RTKLocalizationComponent::Init() {
tf2_broadcaster_.reset(new apollo::transform::TransformBroadcaster(node_));
if (!InitConfig()) {
AERROR << "Init Config falseed.";
return false;
}
if (!InitIO()) {
AERROR << "Init Interval falseed.";
return false;
}
return true;
}
```
InitConfig函数作用是读取配置文件信息,并根据配置文件初始化一个RTKLocalization类的实例
```InitConfig
bool RTKLocalizationComponent::InitConfig() {
rtk_config::Config rtk_config;
if (!apollo::cyber::common::GetProtoFromFile(config_file_path_,
&rtk_config)) {
return false;
}
AINFO << "Rtk localization config: " << rtk_config.DebugString();
localization_topic_ = rtk_config.localization_topic();
localization_status_topic_ = rtk_config.localization_status_topic();
imu_topic_ = rtk_config.imu_topic();
gps_topic_ = rtk_config.gps_topic();
gps_status_topic_ = rtk_config.gps_status_topic();
broadcast_tf_frame_id_ = rtk_config.broadcast_tf_frame_id();
broadcast_tf_child_frame_id_ = rtk_config.broadcast_tf_child_frame_id();
localization_->InitConfig(rtk_config);
return true;
}
```
InitIO函数是在创建需要读取数据的readers并给其绑定对应的回调函数
```InitIO
bool RTKLocalizationComponent::InitIO() {
//监听imu数据,绑定回调函数ImuCallback
corrected_imu_listener_ = node_->CreateReader<localization::CorrectedImu>(
imu_topic_, std::bind(&RTKLocalization::ImuCallback, localization_.get(),
std::placeholders::_1));
ACHECK(corrected_imu_listener_);
//监听gps函数数据绑定回调函数GpsStatusCallback
gps_status_listener_ = node_->CreateReader<drivers::gnss::InsStat>(
gps_status_topic_, std::bind(&RTKLocalization::GpsStatusCallback,
localization_.get(), std::placeholders::_1));
ACHECK(gps_status_listener_);
//创建消息发布者,发布位置信息
localization_talker_ =
node_->CreateWriter<LocalizationEstimate>(localization_topic_);
ACHECK(localization_talker_);
//发布位置状态信息
localization_status_talker_ =
node_->CreateWriter<LocalizationStatus>(localization_status_topic_);
ACHECK(localization_status_talker_);
return true;
}
```
Proc函数中获取位置信息之后会调用三个函数来发布三种和位置相关的消息
```Proc
bool RTKLocalizationComponent::Proc(
const std::shared_ptr<localization::Gps>& gps_msg) {
localization_->GpsCallback(gps_msg);
if (localization_->IsServiceStarted()) {
LocalizationEstimate localization;
localization_->GetLocalization(&localization);
LocalizationStatus localization_status;
localization_->GetLocalizationStatus(&localization_status);
// publish localization messages
//发布位置信息
PublishPoseBroadcastTopic(localization);
//利用Transform 模块的TransformBroadcaster发布坐标转换关系数据
PublishPoseBroadcastTF(localization);
//发布位置相关的一些状态信息
PublishLocalizationStatus(localization_status);
ADEBUG << "[OnTimer]: Localization message publish success!";
}
return true;
}
```
## canbus
### canbus.launch
```
<cyber>
<module>
<name>canbus</name>
<dag_conf>/apollo/modules/canbus/dag/canbus.dag</dag_conf>
<process_name>canbus</process_name>
</module>
</cyber>
```
### canbus.dag
canbus模块也是一个定时模块,CanbusComponent继承Timer_Component定时任务的时间间隔为10ms。
```
module_config {
module_library : "/apollo/bazel-bin/modules/canbus/libcanbus_component.so"
timer_components {
class_name : "CanbusComponent"
config {
name: "canbus"
config_file_path: "/apollo/modules/canbus/conf/canbus_conf.pb.txt"
flag_file_path: "/apollo/modules/canbus/conf/canbus.conf"
interval: 10
}
}
}
```
### CanbusComponent
输入:
/apollo/control
或者
/apollo/guardian
输出:
/apollo/canbus/chassis
/apollo/canbus/chassis_detail
在接受输入时会判断一个FLAGS_receive_guardian是否为true来决定是直接接收control模块的命令还是接收guardian模块封装之后的控制命令
这个flag是在模块的配置文件中进行设置的。
```canbus.conf
--flagfile=/apollo/modules/common/data/global_flagfile.txt
--canbus_conf_file=/apollo/modules/canbus/conf/canbus_conf.pb.txt
--noenable_chassis_detail_pub
--noreceive_guardian
```
修改`--receive_guardian`为`--noreceive_guardian`,就可以关闭guardian模块
### 源码分析
#### CanbusComponent
CanbusComponent::Init函数中除了必要的reader和writer创建之外
主要是创建了can_client、can_receiver、can_sender、vehicle_controller_,然后调用这四者的Start函数来完成canbus模块与车辆底盘的消息交互。
```
// 1. init and start the can card hardware
if (can_client_->Start() != ErrorCode::OK) {
AERROR << "Failed to start can client";
return false;
}
AINFO << "Can client is started.";
// 2. start receive first then send
if (can_receiver_.Start() != ErrorCode::OK) {
AERROR << "Failed to start can receiver.";
return false;
}
AINFO << "Can receiver is started.";
// 3. start send
if (can_sender_.Start() != ErrorCode::OK) {
AERROR << "Failed to start can sender.";
return false;
}
// 4. start controller
if (!vehicle_controller_->Start()) {
AERROR << "Failed to start vehicle controller.";
return false;
}
```
在Proc函数中会调用PublishChassis和PublishChassisDetail函数来发布chassis和chassis_detail消息给其他模块读取
```
bool CanbusComponent::Proc() {
PublishChassis();
if (FLAGS_enable_chassis_detail_pub) {
PublishChassisDetail();
}
return true;
}
```
#### vehicle_controller
首先是这个controller的创建过程
```
...
VehicleFactory vehicle_factory;
vehicle_factory.RegisterVehicleFactory();
auto vehicle_object =
vehicle_factory.CreateVehicle(canbus_conf_.vehicle_parameter());
if (!vehicle_object) {
AERROR << "Failed to create vehicle:";
return false;
}
message_manager_ = vehicle_object->CreateMessageManager();
if (message_manager_ == nullptr) {
AERROR << "Failed to create message manager.";
return false;
}
AINFO << "Message manager is successfully created.";
...
vehicle_controller_ = vehicle_object->CreateVehicleController();
```
RegisterVehicleFactory函数会根据车辆类型返回对应类型的VehicleFactory
```RegisterVehicleFactory
void VehicleFactory::RegisterVehicleFactory() {
Register(apollo::common::LINCOLN_MKZ, []() -> AbstractVehicleFactory * {
return new LincolnVehicleFactory();
});
Register(apollo::common::GEM, []() -> AbstractVehicleFactory * {
return new GemVehicleFactory();
});
Register(apollo::common::LEXUS, []() -> AbstractVehicleFactory * {
return new LexusVehicleFactory();
});
Register(apollo::common::TRANSIT, []() -> AbstractVehicleFactory * {
return new TransitVehicleFactory();
});
Register(apollo::common::GE3, []() -> AbstractVehicleFactory * {
return new Ge3VehicleFactory();
});
Register(apollo::common::WEY, []() -> AbstractVehicleFactory * {
return new WeyVehicleFactory();
});
Register(apollo::common::ZHONGYUN, []() -> AbstractVehicleFactory * {
return new ZhongyunVehicleFactory();
});
Register(apollo::common::CH, []() -> AbstractVehicleFactory * {
return new ChVehicleFactory();
});
Register(apollo::common::DKIT, []() -> AbstractVehicleFactory * {
return new DevkitVehicleFactory();
});
Register(apollo::common::NEOLIX, []() -> AbstractVehicleFactory * {
return new Neolix_eduVehicleFactory();
});
}
```
然后调用VehicleFactory::CreateVehicle函数来根据参数中的brand选取对应的车辆品牌生成对应的vehicle_object
```CreateVehicle
std::unique_ptr<AbstractVehicleFactory> VehicleFactory::CreateVehicle(
const VehicleParameter &vehicle_parameter) {
auto abstract_factory = CreateObject(vehicle_parameter.brand());
if (!abstract_factory) {
AERROR << "failed to create vehicle factory with "
<< vehicle_parameter.DebugString();
} else {
abstract_factory->SetVehicleParameter(vehicle_parameter);
AINFO << "successfully created vehicle factory with "
<< vehicle_parameter.DebugString();
}
return abstract_factory;
}
```
vehicle_object调用CreateVehicleController创建对应车辆的VehicleController
下面以LincolnVehicleFactory为例说明
```LincolnVehicleFactory
std::unique_ptr<VehicleController>
LincolnVehicleFactory::CreateVehicleController() {
return std::unique_ptr<VehicleController>(new lincoln::LincolnController());
}
```
LincolnController初始化时会定义can_sender中的传递的数据格式
```
...
can_sender_->AddMessage(Brake60::ID, brake_60_, false);
can_sender_->AddMessage(Throttle62::ID, throttle_62_, false);
can_sender_->AddMessage(Steering64::ID, steering_64_, false);
can_sender_->AddMessage(Gear66::ID, gear_66_, false);
can_sender_->AddMessage(Turnsignal68::ID, turnsignal_68_, false);
...
```
LincolnController的Start函数中会创建一个线程SecurityDogThreadFunc
```
bool LincolnController::Start() {
if (!is_initialized_) {
AERROR << "LincolnController has NOT been initiated.";
return false;
}
const auto &update_func = [this] { SecurityDogThreadFunc(); };
thread_.reset(new std::thread(update_func));
return true;
}
```
SecurityDogThreadFunc的功能就是检查消息传递过程中can_sender传输的数据的格式是否正常,具体检查逻辑在CheckResponse函数中。
```SecurityDogThreadFunc
void LincolnController::SecurityDogThreadFunc() {
if (can_sender_ == nullptr) {
AERROR << "Failed to run SecurityDogThreadFunc() because can_sender_ is "
"nullptr.";
return;
}
while (!can_sender_->IsRunning()) {
std::this_thread::yield();
}
std::chrono::duration<double, std::micro> default_period{50000};
int64_t start = cyber::Time::Now().ToMicrosecond();
int32_t speed_ctrl_fail = 0;
int32_t steer_ctrl_fail = 0;
while (can_sender_->IsRunning()) {
const Chassis::DrivingMode mode = driving_mode();
bool emergency_mode = false;
// 1. Steer control check
if ((mode == Chassis::COMPLETE_AUTO_DRIVE ||
mode == Chassis::AUTO_STEER_ONLY) &&
!CheckResponse(CHECK_RESPONSE_STEER_UNIT_FLAG, false)) {
++steer_ctrl_fail;
if (steer_ctrl_fail >= kMaxFailAttempt) {
emergency_mode = true;
set_chassis_error_code(Chassis::MANUAL_INTERVENTION);
}
} else {
steer_ctrl_fail = 0;
}
// 2. Speed control check
if ((mode == Chassis::COMPLETE_AUTO_DRIVE ||
mode == Chassis::AUTO_SPEED_ONLY) &&
!CheckResponse(CHECK_RESPONSE_SPEED_UNIT_FLAG, false)) {
++speed_ctrl_fail;
if (speed_ctrl_fail >= kMaxFailAttempt) {
emergency_mode = true;
set_chassis_error_code(Chassis::MANUAL_INTERVENTION);
}
} else {
speed_ctrl_fail = 0;
}
if (CheckChassisError()) {
emergency_mode = true;
}
if (emergency_mode && mode != Chassis::EMERGENCY_MODE) {
Emergency();
}
int64_t end = cyber::Time::Now().ToMicrosecond();
std::chrono::duration<double, std::micro> elapsed{end - start};
if (elapsed < default_period) {
std::this_thread::sleep_for(default_period - elapsed);
start = cyber::Time::Now().ToMicrosecond();
} else {
AERROR_EVERY(100)
<< "Too much time consumption in LincolnController looping process:"
<< elapsed.count();
start = end;
}
}
}
```
#### can_sender
can_sender的Start函数会启用一个线程PowerSendThreadFunc来发送数据
```Start
template <typename SensorType>
common::ErrorCode CanSender<SensorType>::Start() {
if (is_running_) {
AERROR << "Cansender has already started.";
return common::ErrorCode::CANBUS_ERROR;
}
is_running_ = true;
thread_.reset(new std::thread([this] { PowerSendThreadFunc(); }));
return common::ErrorCode::OK;
}
```
PowerSendThreadFunc中有一个循环,每次循环检查发送的消息send_messages_中是否有消息需要进行传输,主要判断方法为NeedSend函数,如果发现其中有新的数据传入则调用can_client_->SendSingleFrame(can_frames)来向底盘发送消息
```PowerSendThreadFunc
...
while (is_running_) {
tm_start = cyber::Time::Now().ToNanosecond() / 1e3;
new_delta_period = INIT_PERIOD;
for (auto &message : send_messages_) {
bool need_send = NeedSend(message, delta_period);
message.UpdateCurrPeriod(delta_period);
new_delta_period = std::min(new_delta_period, message.curr_period());
if (!need_send) {
continue;
}
std::vector<CanFrame> can_frames;
CanFrame can_frame = message.CanFrame();
can_frames.push_back(can_frame);
if (can_client_->SendSingleFrame(can_frames) != common::ErrorCode::OK) {
AERROR << "Send msg failed:" << can_frame.CanFrameString();
}
if (enable_log()) {
ADEBUG << "send_can_frame#" << can_frame.CanFrameString();
}
}
delta_period = new_delta_period;
tm_end = cyber::Time::Now().ToNanosecond() / 1e3;
sleep_interval = delta_period - (tm_end - tm_start);
if (sleep_interval > 0) {
std::this_thread::sleep_for(std::chrono::microseconds(sleep_interval));
} else {
// do not sleep
AWARN << "Too much time for calculation: " << tm_end - tm_start
<< "us is more than minimum period: " << delta_period << "us";
}
}
...
```
CanbusComponent中接收到新的控制指令时会将控制交给OnControlCommand函数处理。该函数首先会判断控制指令数据是否有效,然后调用vehicle_controller_->Update更新can_sender中的数据,最后调用can_sender_.Update函数。
```OnControlCommand
void CanbusComponent::OnControlCommand(const ControlCommand &control_command) {
int64_t current_timestamp = Time::Now().ToMicrosecond();
// if command coming too soon, just ignore it.
if (current_timestamp - last_timestamp_ < FLAGS_min_cmd_interval * 1000) {
ADEBUG << "Control command comes too soon. Ignore.\n Required "
"FLAGS_min_cmd_interval["
<< FLAGS_min_cmd_interval << "], actual time interval["
<< current_timestamp - last_timestamp_ << "].";
return;
}
last_timestamp_ = current_timestamp;
ADEBUG << "Control_sequence_number:"
<< control_command.header().sequence_num() << ", Time_of_delay:"
<< current_timestamp -
static_cast<int64_t>(control_command.header().timestamp_sec() *
1e6)
<< " micro seconds";
if (vehicle_controller_->Update(control_command) != ErrorCode::OK) {
AERROR << "Failed to process callback function OnControlCommand because "
"vehicle_controller_->Update error.";
return;
}
can_sender_.Update();
}
```
在vehicle_controller_->Update函数中会调用Throttle、Brake等方法将对应的数据更新。
```
...
Gear(control_command.gear_location());
Throttle(control_command.throttle());
Acceleration(control_command.acceleration());
Brake(control_command.brake());
SetEpbBreak(control_command);
SetLimits();
...
```
然后can_sender的Update函数会依次调用每一类message的Update函数,然后最终调用的是每一种数据结构对应的UpdateData函数
```
void CanSender<SensorType>::Update() {
for (auto &message : send_messages_) {
message.Update();
}
}
template <typename SensorType>
void SenderMessage<SensorType>::Update() {
if (protocol_data_ == nullptr) {
AERROR << "Attention: ProtocolData is nullptr!";
return;
}
protocol_data_->UpdateData(can_frame_to_update_.data);
std::lock_guard<std::mutex> lock(mutex_);
can_frame_to_send_ = can_frame_to_update_;
}
```
以Brake60为例,UpdateData函数也是在设置这一个数据结构中不同的变量值。
```
void Brake60::UpdateData(uint8_t *data) {
set_pedal_p(data, pedal_cmd_);
set_boo_cmd_p(data, boo_cmd_);
set_enable_p(data, pedal_enable_);
set_clear_driver_override_flag_p(data, clear_driver_override_flag_);
set_watchdog_counter_p(data, watchdog_counter_);
}
```
#### can_receiver
can_receiver的Start函数会创建一个线程RecvThreadFunc来接收车辆的消息。
```Start
template <typename SensorType>
::apollo::common::ErrorCode CanReceiver<SensorType>::Start() {
if (is_init_ == false) {
return ::apollo::common::ErrorCode::CANBUS_ERROR;
}
is_running_.exchange(true);
async_result_ = cyber::Async(&CanReceiver<SensorType>::RecvThreadFunc, this);
return ::apollo::common::ErrorCode::OK;
}
```
RecvThreadFunc线程中有一个循环,每一次循环都调用can_client_->Receive来接收车辆底盘的消息
```RecvThreadFunc
...
while (IsRunning()) {
std::vector<CanFrame> buf;
int32_t frame_num = MAX_CAN_RECV_FRAME_LEN;
if (can_client_->Receive(&buf, &frame_num) !=
::apollo::common::ErrorCode::OK) {
LOG_IF_EVERY_N(ERROR, receive_error_count++ > ERROR_COUNT_MAX,
ERROR_COUNT_MAX)
<< "Received " << receive_error_count << " error messages.";
cyber::USleep(default_period);
continue;
}
receive_error_count = 0;
if (buf.size() != static_cast<size_t>(frame_num)) {
AERROR_EVERY(100) << "Receiver buf size [" << buf.size()
<< "] does not match can_client returned length["
<< frame_num << "].";
}
if (frame_num == 0) {
LOG_IF_EVERY_N(ERROR, receive_none_count++ > ERROR_COUNT_MAX,
ERROR_COUNT_MAX)
<< "Received " << receive_none_count << " empty messages.";
cyber::USleep(default_period);
continue;
}
receive_none_count = 0;
for (const auto &frame : buf) {
uint8_t len = frame.len;
uint32_t uid = frame.id;
const uint8_t *data = frame.data;
pt_manager_->Parse(uid, data, len);
if (enable_log_) {
ADEBUG << "recv_can_frame#" << frame.CanFrameString();
}
}
cyber::Yield();
}
...
```
接收到消息后会调用pt_manager_->Parse(uid, data, len);函数来处理消息,pt_manager_就是每一种Vehicle对应的MessageManager
。在MessageManager::Parse函数中会调用每种数据结构对应的Parse函数来处理并将数据存储到MessageManager的sensor_data_中。每一种Vehicle都有对应的protocol_data数据类型,如lincoln类型的数据类型定义在/modules/canbus/vehicle/lincoln/protocol下。
```Parse
void MessageManager<SensorType>::Parse(const uint32_t message_id,
const uint8_t *data, int32_t length) {
ProtocolData<SensorType> *protocol_data =
GetMutableProtocolDataById(message_id);
if (protocol_data == nullptr) {
return;
}
{
std::lock_guard<std::mutex> lock(sensor_data_mutex_);
protocol_data->Parse(data, length, &sensor_data_);
}
received_ids_.insert(message_id);
// check if need to check period
const auto it = check_ids_.find(message_id);
if (it != check_ids_.end()) {
const int64_t time = Time::Now().ToNanosecond() / 1e3;
it->second.real_period = time - it->second.last_time;
// if period 1.5 large than base period, inc error_count
const double period_multiplier = 1.5;
if (static_cast<double>(it->second.real_period) >
(static_cast<double>(it->second.period) * period_multiplier)) {
it->second.error_count += 1;
} else {
it->second.error_count = 0;
}
it->second.last_time = time;
}
}
```
然后CanbusComponent::PublishChassis和CanbusComponent::PublishChassisDetail会获取message_manager_的sensor_data存储到chassis_detail中
而PublishChassis则需要调用vehicle_controller_->chassis函数从chassis_detail数据中构造chassis数据返回。
```CanbusComponent::PublishChassis
void CanbusComponent::PublishChassis() {
Chassis chassis = vehicle_controller_->chassis();
common::util::FillHeader(node_->Name(), &chassis);
chassis_writer_->Write(chassis);
ADEBUG << chassis.ShortDebugString();
}
void CanbusComponent::PublishChassisDetail() {
ChassisDetail chassis_detail;
message_manager_->GetSensorData(&chassis_detail);
ADEBUG << chassis_detail.ShortDebugString();
chassis_detail_writer_->Write(chassis_detail);
}
```