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" 36 namespace localization {
46 bool Proc(
const std::shared_ptr<localization::Gps> &gps_msg)
override;
52 void PublishPoseBroadcastTF(
const LocalizationEstimate &localization);
53 void PublishPoseBroadcastTopic(
const LocalizationEstimate &localization);
54 void PublishLocalizationStatus(
const LocalizationStatus &localization_status);
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_ =
62 std::shared_ptr<cyber::Writer<LocalizationEstimate>> localization_talker_ =
64 std::shared_ptr<cyber::Writer<LocalizationStatus>>
65 localization_status_talker_ =
nullptr;
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_ =
"";
73 std::string broadcast_tf_frame_id_ =
"";
74 std::string broadcast_tf_child_frame_id_ =
"";
75 std::unique_ptr<apollo::transform::TransformBroadcaster> tf2_broadcaster_;
77 std::unique_ptr<RTKLocalization> localization_;
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
~RTKLocalizationComponent()=default
Definition: rtk_localization_component.h:38
CYBER_REGISTER_COMPONENT(MSFLocalizationComponent)
RTKLocalizationComponent()
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58