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" 38 namespace localization {
48 bool Proc(
const std::shared_ptr<drivers::gnss::Imu>& imu_msg)
override;
55 std::shared_ptr<cyber::Reader<drivers::PointCloud>> lidar_listener_ =
nullptr;
56 std::string lidar_topic_ =
"";
58 std::shared_ptr<cyber::Reader<drivers::gnss::GnssBestPose>>
59 bestgnsspos_listener_ =
nullptr;
60 std::string bestgnsspos_topic_ =
"";
62 std::shared_ptr<cyber::Reader<drivers::gnss::Heading>>
63 gnss_heading_listener_ =
nullptr;
64 std::string gnss_heading_topic_ =
"";
67 std::shared_ptr<LocalizationMsgPublisher> publisher_;
71 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
84 void PublishPoseBroadcastTF(
const LocalizationEstimate& localization);
85 void PublishPoseBroadcastTopic(
const LocalizationEstimate& localization);
87 void PublishLocalizationMsfGnss(
const LocalizationEstimate& localization);
88 void PublishLocalizationMsfLidar(
const LocalizationEstimate& localization);
89 void PublishLocalizationStatus(
const LocalizationStatus& localization_status);
92 std::shared_ptr<cyber::Node>
node_;
94 std::string localization_topic_ =
"";
95 std::shared_ptr<cyber::Writer<LocalizationEstimate>> localization_talker_ =
98 std::string broadcast_tf_frame_id_ =
"";
99 std::string broadcast_tf_child_frame_id_ =
"";
102 std::string lidar_local_topic_ =
"";
103 std::shared_ptr<cyber::Writer<LocalizationEstimate>> lidar_local_talker_ =
106 std::string gnss_local_topic_ =
"";
107 std::shared_ptr<cyber::Writer<LocalizationEstimate>> gnss_local_talker_ =
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;
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
MSFLocalizationComponent()
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58
~MSFLocalizationComponent()=default