Apollo 10.0
自动驾驶开放平台
apollo::drivers::gnss::RawStream类 参考

#include <raw_stream.h>

apollo::drivers::gnss::RawStream 的协作图:

struct  Status
 

Public 成员函数

 RawStream (const config::Config &config, const std::shared_ptr< apollo::cyber::Node > &node)
 
 ~RawStream ()
 
bool Init ()
 
void Start ()
 

详细描述

在文件 raw_stream.h38 行定义.

构造及析构函数说明

◆ RawStream()

apollo::drivers::gnss::RawStream::RawStream ( const config::Config config,
const std::shared_ptr< apollo::cyber::Node > &  node 
)

在文件 raw_stream.cc160 行定义.

162 : config_(config), node_(node) {
163 data_parser_ptr_.reset(new DataParser(config_, node_));
164 rtcm_parser_ptr_.reset(new RtcmParser(config_, node_));
165}

◆ ~RawStream()

apollo::drivers::gnss::RawStream::~RawStream ( )

在文件 raw_stream.cc167 行定义.

167 {
168 this->Logout();
169 this->Disconnect();
170 if (gpsbin_stream_ != nullptr) {
171 gpsbin_stream_->close();
172 }
173 if (data_thread_ptr_ != nullptr && data_thread_ptr_->joinable()) {
174 data_thread_ptr_->join();
175 }
176 if (rtk_thread_ptr_ != nullptr && rtk_thread_ptr_->joinable()) {
177 rtk_thread_ptr_->join();
178 }
179}

成员函数说明

◆ Init()

bool apollo::drivers::gnss::RawStream::Init ( )

在文件 raw_stream.cc181 行定义.

181 {
182 CHECK_NOTNULL(data_parser_ptr_);
183 CHECK_NOTNULL(rtcm_parser_ptr_);
184 if (!data_parser_ptr_->Init()) {
185 AERROR << "Init data parser failed.";
186 return false;
187 }
188 if (!rtcm_parser_ptr_->Init()) {
189 AERROR << "Init rtcm parser failed.";
190 return false;
191 }
192 stream_status_.set_ins_stream_type(StreamStatus::DISCONNECTED);
193 stream_status_.set_rtk_stream_in_type(StreamStatus::DISCONNECTED);
194 stream_status_.set_rtk_stream_out_type(StreamStatus::DISCONNECTED);
195 stream_writer_ = node_->CreateWriter<StreamStatus>(FLAGS_stream_status_topic);
196
197 common::util::FillHeader("gnss", &stream_status_);
198 stream_writer_->Write(stream_status_);
199
200 // Creates streams.
201 Stream *s = nullptr;
202 if (!config_.has_data()) {
203 AINFO << "Error: Config file must provide the data stream.";
204 return false;
205 }
206 s = create_stream(config_.data());
207 if (s == nullptr) {
208 AERROR << "Failed to create data stream.";
209 return false;
210 }
211 data_stream_.reset(s);
212
213 Status *status = new Status();
214 if (!status) {
215 AERROR << "Failed to create data stream status.";
216 return false;
217 }
218 data_stream_status_.reset(status);
219
220 if (config_.has_command()) {
221 s = create_stream(config_.command());
222 if (s == nullptr) {
223 AERROR << "Failed to create command stream.";
224 return false;
225 }
226 command_stream_.reset(s);
227
228 status = new Status();
229 if (!status) {
230 AERROR << "Failed to create command stream status.";
231 return false;
232 }
233 command_stream_status_.reset(status);
234 } else {
235 command_stream_ = data_stream_;
236 command_stream_status_ = data_stream_status_;
237 }
238
239 if (config_.has_rtk_from()) {
240 s = create_stream(config_.rtk_from());
241 if (s == nullptr) {
242 AERROR << "Failed to create rtk_from stream.";
243 return false;
244 }
245 in_rtk_stream_.reset(s);
246
247 if (config_.rtk_from().has_push_location()) {
248 push_location_ = config_.rtk_from().push_location();
249 }
250
251 status = new Status();
252 if (!status) {
253 AERROR << "Failed to create rtk_from stream status.";
254 return false;
255 }
256 in_rtk_stream_status_.reset(status);
257
258 if (config_.has_rtk_to()) {
259 s = create_stream(config_.rtk_to());
260 if (s == nullptr) {
261 AERROR << "Failed to create rtk_to stream.";
262 return false;
263 }
264 out_rtk_stream_.reset(s);
265
266 status = new Status();
267 if (!status) {
268 AERROR << "Failed to create rtk_to stream status.";
269 return false;
270 }
271 out_rtk_stream_status_.reset(status);
272 } else {
273 out_rtk_stream_ = data_stream_;
274 out_rtk_stream_status_ = data_stream_status_;
275 }
276
277 if (config_.has_rtk_solution_type()) {
278 if (config_.rtk_solution_type() ==
280 rtk_software_solution_ = true;
281 }
282 }
283 }
284
285 if (config_.login_commands().empty()) {
286 AWARN << "No login_commands in config file.";
287 }
288
289 if (config_.logout_commands().empty()) {
290 AWARN << "No logout_commands in config file.";
291 }
292
293 // connect and login
294 if (!Connect()) {
295 AERROR << "gnss driver connect failed.";
296 return false;
297 }
298
299 if (!Login()) {
300 AERROR << "gnss driver login failed.";
301 return false;
302 }
303
304 const std::string gpsbin_file = getLocalTimeFileStr(config_.gpsbin_folder());
305 gpsbin_stream_.reset(new std::ofstream(
306 gpsbin_file, std::ios::app | std::ios::out | std::ios::binary));
307 stream_writer_ = node_->CreateWriter<StreamStatus>(FLAGS_stream_status_topic);
308 raw_writer_ = node_->CreateWriter<RawData>(FLAGS_gnss_raw_data_topic);
309 rtcm_writer_ = node_->CreateWriter<RawData>(FLAGS_rtcm_data_topic);
310 cyber::ReaderConfig reader_config;
311 reader_config.channel_name = FLAGS_gnss_raw_data_topic;
312 reader_config.pending_queue_size = 100;
313 gpsbin_reader_ = node_->CreateReader<RawData>(
314 reader_config, [&](const std::shared_ptr<RawData> &raw_data) {
315 GpsbinCallback(raw_data);
316 });
317 chassis_reader_ = node_->CreateReader<Chassis>(
318 FLAGS_chassis_topic,
319 [&](const std::shared_ptr<Chassis> &chassis) { chassis_ptr_ = chassis; });
320
321 return true;
322}
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
Stream * create_stream(const config::Stream &sd)
Definition raw_stream.cc:73
std::string getLocalTimeFileStr(const std::string &gpsbin_folder)
Definition raw_stream.cc:57
optional RtkSolutionType rtk_solution_type
Definition config.proto:133

◆ Start()

void apollo::drivers::gnss::RawStream::Start ( )

在文件 raw_stream.cc324 行定义.

324 {
325 data_thread_ptr_.reset(new std::thread(&RawStream::DataSpin, this));
326 rtk_thread_ptr_.reset(new std::thread(&RawStream::RtkSpin, this));
327 if (config_.has_wheel_parameters()) {
328 wheel_velocity_timer_.reset(new cyber::Timer(
329 1000, [this]() { this->OnWheelVelocityTimer(); }, false));
330 wheel_velocity_timer_->Start();
331 }
332}

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