Apollo  6.0
Open source self driving car software
rtk_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 
27 #include "modules/drivers/gnss/proto/ins.pb.h"
28 #include "modules/localization/proto/gps.pb.h"
29 #include "modules/localization/proto/imu.pb.h"
30 #include "modules/localization/proto/localization.pb.h"
31 #include "modules/localization/proto/rtk_config.pb.h"
34 
35 namespace apollo {
36 namespace localization {
37 
39  : public cyber::Component<localization::Gps> {
40  public:
42  ~RTKLocalizationComponent() = default;
43 
44  bool Init() override;
45 
46  bool Proc(const std::shared_ptr<localization::Gps> &gps_msg) override;
47 
48  private:
49  bool InitConfig();
50  bool InitIO();
51 
52  void PublishPoseBroadcastTF(const LocalizationEstimate &localization);
53  void PublishPoseBroadcastTopic(const LocalizationEstimate &localization);
54  void PublishLocalizationStatus(const LocalizationStatus &localization_status);
55 
56  private:
57  std::shared_ptr<cyber::Reader<localization::CorrectedImu>>
58  corrected_imu_listener_ = nullptr;
59  std::shared_ptr<cyber::Reader<drivers::gnss::InsStat>> gps_status_listener_ =
60  nullptr;
61 
62  std::shared_ptr<cyber::Writer<LocalizationEstimate>> localization_talker_ =
63  nullptr;
64  std::shared_ptr<cyber::Writer<LocalizationStatus>>
65  localization_status_talker_ = nullptr;
66 
67  std::string localization_topic_ = "";
68  std::string localization_status_topic_ = "";
69  std::string gps_topic_ = "";
70  std::string gps_status_topic_ = "";
71  std::string imu_topic_ = "";
72 
73  std::string broadcast_tf_frame_id_ = "";
74  std::string broadcast_tf_child_frame_id_ = "";
75  std::unique_ptr<apollo::transform::TransformBroadcaster> tf2_broadcaster_;
76 
77  std::unique_ptr<RTKLocalization> localization_;
78 };
79 
81 
82 } // namespace localization
83 } // namespace apollo
bool Proc(const std::shared_ptr< localization::Gps > &gps_msg) override
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: rtk_localization_component.h:38
CYBER_REGISTER_COMPONENT(MSFLocalizationComponent)
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58