Apollo  6.0
Open source self driving car software
msf_localization_component.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2017 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 
24 #include "cyber/cyber.h"
26 
28 
29 #include "modules/drivers/gnss/proto/gnss_best_pose.pb.h"
30 #include "modules/drivers/gnss/proto/gnss_raw_observation.pb.h"
31 #include "modules/drivers/gnss/proto/imu.pb.h"
32 #include "modules/drivers/proto/pointcloud.pb.h"
33 #include "modules/localization/proto/gps.pb.h"
34 #include "modules/localization/proto/localization.pb.h"
36 
37 namespace apollo {
38 namespace localization {
39 
41  : public cyber::Component<drivers::gnss::Imu> {
42  public:
44  ~MSFLocalizationComponent() = default;
45 
46  bool Init() override;
47 
48  bool Proc(const std::shared_ptr<drivers::gnss::Imu>& imu_msg) override;
49 
50  private:
51  bool InitConfig();
52  bool InitIO();
53 
54  private:
55  std::shared_ptr<cyber::Reader<drivers::PointCloud>> lidar_listener_ = nullptr;
56  std::string lidar_topic_ = "";
57 
58  std::shared_ptr<cyber::Reader<drivers::gnss::GnssBestPose>>
59  bestgnsspos_listener_ = nullptr;
60  std::string bestgnsspos_topic_ = "";
61 
62  std::shared_ptr<cyber::Reader<drivers::gnss::Heading>>
63  gnss_heading_listener_ = nullptr;
64  std::string gnss_heading_topic_ = "";
65 
66  private:
67  std::shared_ptr<LocalizationMsgPublisher> publisher_;
68  MSFLocalization localization_;
69 
70  public:
71  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
72 };
73 
75 
77  public:
78  explicit LocalizationMsgPublisher(const std::shared_ptr<cyber::Node>& node);
79  ~LocalizationMsgPublisher() = default;
80 
81  bool InitConfig();
82  bool InitIO();
83 
84  void PublishPoseBroadcastTF(const LocalizationEstimate& localization);
85  void PublishPoseBroadcastTopic(const LocalizationEstimate& localization);
86 
87  void PublishLocalizationMsfGnss(const LocalizationEstimate& localization);
88  void PublishLocalizationMsfLidar(const LocalizationEstimate& localization);
89  void PublishLocalizationStatus(const LocalizationStatus& localization_status);
90 
91  private:
92  std::shared_ptr<cyber::Node> node_;
93 
94  std::string localization_topic_ = "";
95  std::shared_ptr<cyber::Writer<LocalizationEstimate>> localization_talker_ =
96  nullptr;
97 
98  std::string broadcast_tf_frame_id_ = "";
99  std::string broadcast_tf_child_frame_id_ = "";
101 
102  std::string lidar_local_topic_ = "";
103  std::shared_ptr<cyber::Writer<LocalizationEstimate>> lidar_local_talker_ =
104  nullptr;
105 
106  std::string gnss_local_topic_ = "";
107  std::shared_ptr<cyber::Writer<LocalizationEstimate>> gnss_local_talker_ =
108  nullptr;
109 
110  std::string localization_status_topic_ = "";
111  std::shared_ptr<cyber::Writer<LocalizationStatus>>
112  localization_status_talker_ = nullptr;
113  double pre_system_time_ = 0.0;
114 };
115 
116 } // namespace localization
117 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool Proc(const std::shared_ptr< drivers::gnss::Imu > &imu_msg) override
CYBER_REGISTER_COMPONENT(MSFLocalizationComponent)
The class of MSFLocalization.
Definition: msf_localization_component.h:40
Definition: msf_localization_component.h:76
generate localization info based on MSF
Definition: msf_localization.h:58
std::shared_ptr< Node > node_
Definition: component_base.h:113
This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message.
Definition: transform_broadcaster.h:34
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58