Apollo 10.0
自动驾驶开放平台
ndt_localization_component.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
17#pragma once
18
19#include <memory>
20#include <string>
21#include <vector>
22
25#include "cyber/cyber.h"
27
28#include "modules/common_msgs/sensor_msgs/ins.pb.h"
29#include "modules/common_msgs/sensor_msgs/pointcloud.pb.h"
31#include "modules/common_msgs/localization_msgs/gps.pb.h"
32#include "modules/common_msgs/localization_msgs/localization.pb.h"
34
35namespace apollo {
36namespace localization {
37namespace ndt {
38
40 : public cyber::Component<localization::Gps> {
41 public:
44
45 bool Init() override;
46
47 bool Proc(const std::shared_ptr<localization::Gps> &odometry_msg) override;
48
49 private:
50 bool InitConfig();
51 bool InitIO();
52
53 void LidarCallback(const std::shared_ptr<drivers::PointCloud> &lidar_msg);
54 void OdometryStatusCallback(
55 const std::shared_ptr<drivers::gnss::InsStat> &status_msg);
56
57 void PublishPoseBroadcastTF(const LocalizationEstimate &localization);
58 void PublishPoseBroadcastTopic(const LocalizationEstimate &localization);
59 void PublishLidarPoseBroadcastTopic(const LocalizationEstimate &localization);
60 void PublishLocalizationStatusTopic(
61 const LocalizationStatus &localization_status);
62
63 private:
64 std::shared_ptr<cyber::Reader<drivers::PointCloud>> lidar_listener_ = nullptr;
65
66 std::shared_ptr<cyber::Reader<drivers::gnss::InsStat>>
67 odometry_status_listener_ = nullptr;
68
69 std::shared_ptr<cyber::Writer<LocalizationEstimate>> localization_talker_ =
70 nullptr;
71
72 std::shared_ptr<cyber::Writer<LocalizationEstimate>> lidar_pose_talker_ =
73 nullptr;
74
75 std::shared_ptr<cyber::Writer<LocalizationStatus>>
76 localization_status_talker_ = nullptr;
77
78 std::string lidar_topic_ = "";
79 std::string odometry_topic_ = "";
80 std::string localization_topic_ = "";
81 std::string lidar_pose_topic_ = "";
82 std::string odometry_status_topic_ = "";
83 std::string localization_status_topic_ = "";
84
85 std::string broadcast_tf_frame_id_ = "";
86 std::string broadcast_tf_child_frame_id_ = "";
87 std::unique_ptr<apollo::transform::TransformBroadcaster> tf2_broadcaster_;
88
89 std::unique_ptr<NDTLocalization> localization_;
90};
91
93
94} // namespace ndt
95} // namespace localization
96} // namespace apollo
bool Proc(const std::shared_ptr< localization::Gps > &odometry_msg) override
#define CYBER_REGISTER_COMPONENT(name)
Definition component.h:656
class register implement
Definition arena_queue.h:37