Apollo 10.0
自动驾驶开放平台
apollo::localization::LocalizationMsgPublisher类 参考

#include <msf_localization_component.h>

apollo::localization::LocalizationMsgPublisher 的协作图:

Public 成员函数

 LocalizationMsgPublisher (const std::shared_ptr< cyber::Node > &node)
 
 ~LocalizationMsgPublisher ()=default
 
bool InitConfig ()
 
bool InitIO ()
 
void PublishPoseBroadcastTF (const LocalizationEstimate &localization)
 
void PublishPoseBroadcastTopic (const LocalizationEstimate &localization)
 
void PublishLocalizationMsfGnss (const LocalizationEstimate &localization)
 
void PublishLocalizationMsfLidar (const LocalizationEstimate &localization)
 
void PublishLocalizationStatus (const LocalizationStatus &localization_status)
 

详细描述

在文件 msf_localization_component.h77 行定义.

构造及析构函数说明

◆ LocalizationMsgPublisher()

apollo::localization::LocalizationMsgPublisher::LocalizationMsgPublisher ( const std::shared_ptr< cyber::Node > &  node)
explicit

在文件 msf_localization_component.cc109 行定义.

111 : node_(node), localization_gnss_compensator_(
112 LocalizationGnssCompensator::Instance()),
113 tf2_broadcaster_(node) {}

◆ ~LocalizationMsgPublisher()

apollo::localization::LocalizationMsgPublisher::~LocalizationMsgPublisher ( )
default

成员函数说明

◆ InitConfig()

bool apollo::localization::LocalizationMsgPublisher::InitConfig ( )

在文件 msf_localization_component.cc115 行定义.

115 {
116 localization_topic_ = FLAGS_localization_topic;
117 broadcast_tf_frame_id_ = FLAGS_broadcast_tf_frame_id;
118 broadcast_tf_child_frame_id_ = FLAGS_broadcast_tf_child_frame_id;
119 lidar_local_topic_ = FLAGS_localization_lidar_topic;
120 gnss_local_topic_ = FLAGS_localization_gnss_topic;
121 localization_status_topic_ = FLAGS_localization_msf_status;
122
123 return true;
124}

◆ InitIO()

bool apollo::localization::LocalizationMsgPublisher::InitIO ( )

在文件 msf_localization_component.cc126 行定义.

126 {
127 localization_talker_ =
128 node_->CreateWriter<LocalizationEstimate>(localization_topic_);
129
130 lidar_local_talker_ =
131 node_->CreateWriter<LocalizationEstimate>(lidar_local_topic_);
132
133 gnss_local_talker_ =
134 node_->CreateWriter<LocalizationEstimate>(gnss_local_topic_);
135
136 localization_status_talker_ =
137 node_->CreateWriter<LocalizationStatus>(localization_status_topic_);
138 return true;
139}

◆ PublishLocalizationMsfGnss()

void apollo::localization::LocalizationMsgPublisher::PublishLocalizationMsfGnss ( const LocalizationEstimate localization)

在文件 msf_localization_component.cc198 行定义.

199 {
200 gnss_local_talker_->Write(localization);
201}

◆ PublishLocalizationMsfLidar()

void apollo::localization::LocalizationMsgPublisher::PublishLocalizationMsfLidar ( const LocalizationEstimate localization)

在文件 msf_localization_component.cc203 行定义.

204 {
205 lidar_local_talker_->Write(localization);
206}

◆ PublishLocalizationStatus()

void apollo::localization::LocalizationMsgPublisher::PublishLocalizationStatus ( const LocalizationStatus localization_status)

在文件 msf_localization_component.cc208 行定义.

209 {
210 localization_status_talker_->Write(localization_status);
211}

◆ PublishPoseBroadcastTF()

void apollo::localization::LocalizationMsgPublisher::PublishPoseBroadcastTF ( const LocalizationEstimate localization)

在文件 msf_localization_component.cc141 行定义.

142 {
143 // broadcast tf message
145 // uint64_t compensated_delta;
146 uint64_t current_send_tf_time = apollo::cyber::Clock::Now().ToNanosecond();
147 uint64_t measurement_time =
148 apollo::cyber::Time(localization.measurement_time()).ToNanosecond();
149
150 auto mutable_head = tf2_msg.mutable_header();
151
152 localization_gnss_compensator_ = LocalizationGnssCompensator::Instance();
153
154 localization_gnss_compensator_->ProcessCompensation(
155 current_send_tf_time, &measurement_time);
156
157 mutable_head->set_timestamp_sec(
158 apollo::cyber::Time(measurement_time).ToSecond());
159 mutable_head->set_frame_id(broadcast_tf_frame_id_);
160 tf2_msg.set_child_frame_id(broadcast_tf_child_frame_id_);
161
162 auto mutable_translation = tf2_msg.mutable_transform()->mutable_translation();
163 mutable_translation->set_x(localization.pose().position().x());
164 mutable_translation->set_y(localization.pose().position().y());
165 mutable_translation->set_z(localization.pose().position().z());
166
167 auto mutable_rotation = tf2_msg.mutable_transform()->mutable_rotation();
168 mutable_rotation->set_qx(localization.pose().orientation().qx());
169 mutable_rotation->set_qy(localization.pose().orientation().qy());
170 mutable_rotation->set_qz(localization.pose().orientation().qz());
171 mutable_rotation->set_qw(localization.pose().orientation().qw());
172
173 tf2_broadcaster_.SendTransform(tf2_msg);
174}
static Time Now()
PRECISION >= 1000000 means the precision is at least 1us.
Definition clock.cc:40
Cyber has builtin time type Time.
Definition time.h:31
uint64_t ToNanosecond() const
convert time to nanosecond.
Definition time.cc:83
void ProcessCompensation(const uint64_t &current_send_tf_time, uint64_t *measurement_time)
compensate the time parsed from invalid GNSS data
void SendTransform(const TransformStamped &transform)
Send a TransformStamped message The stamped data structure includes frame_id, and time,...

◆ PublishPoseBroadcastTopic()

void apollo::localization::LocalizationMsgPublisher::PublishPoseBroadcastTopic ( const LocalizationEstimate localization)

在文件 msf_localization_component.cc176 行定义.

177 {
178 double cur_system_time = localization.header().timestamp_sec();
179 if (pre_system_time_ > 0.0 && cur_system_time - pre_system_time_ > 0.02) {
180 AERROR << std::setprecision(16)
181 << "the localization processing time enlonged more than 2 times "
182 "according to system time, "
183 << "the pre system time and current system time: "
184 << pre_system_time_ << " " << cur_system_time;
185 } else if (pre_system_time_ > 0.0 &&
186 cur_system_time - pre_system_time_ < 0.0) {
187 AERROR << std::setprecision(16)
188 << "published localization message's time is eary than last imu "
189 "message "
190 "according to system time, "
191 << "the pre system time and current system time: "
192 << pre_system_time_ << " " << cur_system_time;
193 }
194 pre_system_time_ = cur_system_time;
195 localization_talker_->Write(localization);
196}
#define AERROR
Definition log.h:44

该类的文档由以下文件生成: