Apollo 10.0
自动驾驶开放平台
velodyne_convert_component.h
浏览该文件的文档.
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#pragma once
18
19#include <deque>
20#include <memory>
21#include <string>
22#include <thread>
23
24#include "modules/drivers/lidar/proto/velodyne.pb.h"
25#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
26
28#include "cyber/cyber.h"
30
31namespace apollo {
32namespace drivers {
33namespace velodyne {
34
41
42class VelodyneConvertComponent : public Component<VelodyneScan> {
43 public:
44 bool Init() override;
45 bool Proc(const std::shared_ptr<VelodyneScan>& scan_msg) override;
46
47 private:
48 std::shared_ptr<Writer<PointCloud>> writer_;
49 std::unique_ptr<Convert> conv_ = nullptr;
50 std::shared_ptr<CCObjectPool<PointCloud>> point_cloud_pool_ = nullptr;
51 int pool_size_ = 8;
52};
53
55
56} // namespace velodyne
57} // namespace drivers
58} // namespace apollo
Reader subscribes a channel, it has two main functions:
Definition reader.h:69
bool Proc(const std::shared_ptr< VelodyneScan > &scan_msg) override
#define CYBER_REGISTER_COMPONENT(name)
Definition component.h:656
class register implement
Definition arena_queue.h:37