Apollo 10.0
自动驾驶开放平台
velodyne_convert_component.cc
浏览该文件的文档.
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#include <memory>
18#include <string>
19#include <thread>
20
21#include "cyber/cyber.h"
22
24
25namespace apollo {
26namespace drivers {
27namespace velodyne {
28
30 Config velodyne_config;
31 if (!GetProtoConfig(&velodyne_config)) {
32 AWARN << "Load config failed, config file" << config_file_path_;
33 return false;
34 }
35
36 conv_.reset(new Convert());
37 conv_->init(velodyne_config);
38 writer_ =
39 node_->CreateWriter<PointCloud>(velodyne_config.convert_channel_name());
40 point_cloud_pool_.reset(new CCObjectPool<PointCloud>(pool_size_));
41 point_cloud_pool_->ConstructAll();
42 for (int i = 0; i < pool_size_; i++) {
43 auto point_cloud = point_cloud_pool_->GetObject();
44 if (point_cloud == nullptr) {
45 AERROR << "fail to getobject, i: " << i;
46 return false;
47 }
48 point_cloud->mutable_point()->Reserve(140000);
49 }
50 AINFO << "Point cloud comp convert init success";
51 return true;
52}
53
55 const std::shared_ptr<VelodyneScan>& scan_msg) {
56 std::shared_ptr<PointCloud> point_cloud_out = point_cloud_pool_->GetObject();
57 if (point_cloud_out == nullptr) {
58 AWARN << "poin cloud pool return nullptr, will be create new.";
59 point_cloud_out = std::make_shared<PointCloud>();
60 point_cloud_out->mutable_point()->Reserve(140000);
61 }
62 if (point_cloud_out == nullptr) {
63 AWARN << "point cloud out is nullptr";
64 return false;
65 }
66 point_cloud_out->Clear();
67 conv_->ConvertPacketsToPointcloud(scan_msg, point_cloud_out);
68
69 if (point_cloud_out == nullptr || point_cloud_out->point().empty()) {
70 AWARN << "point_cloud_out convert is empty.";
71 return false;
72 }
73 writer_->Write(point_cloud_out);
74 return true;
75}
76
77} // namespace velodyne
78} // namespace drivers
79} // namespace apollo
bool GetProtoConfig(T *config) const
std::shared_ptr< Node > node_
bool Proc(const std::shared_ptr< VelodyneScan > &scan_msg) override
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
class register implement
Definition arena_queue.h:37