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
27
#include "
cyber/base/concurrent_object_pool.h
"
28
#include "
cyber/cyber.h
"
29
#include "
modules/drivers/lidar/velodyne/parser/convert.h
"
30
31
namespace
apollo
{
32
namespace
drivers {
33
namespace
velodyne {
34
35
using
apollo::cyber::Component
;
36
using
apollo::cyber::Reader
;
37
using
apollo::cyber::Writer
;
38
using
apollo::cyber::base::CCObjectPool
;
39
using
apollo::drivers::PointCloud
;
40
using
apollo::drivers::velodyne::VelodyneScan
;
41
42
class
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
54
CYBER_REGISTER_COMPONENT
(
VelodyneConvertComponent
)
55
56
}
// namespace velodyne
57
}
// namespace drivers
58
}
// namespace apollo
apollo::cyber::Component
Definition
component.h:60
apollo::cyber::Reader
Reader subscribes a channel, it has two main functions:
Definition
reader.h:69
apollo::cyber::Writer
Definition
writer.h:42
apollo::cyber::base::CCObjectPool
Definition
concurrent_object_pool.h:36
apollo::drivers::velodyne::VelodyneConvertComponent
Definition
velodyne_convert_component.h:42
apollo::drivers::velodyne::VelodyneConvertComponent::Proc
bool Proc(const std::shared_ptr< VelodyneScan > &scan_msg) override
Definition
velodyne_convert_component.cc:54
apollo::drivers::velodyne::VelodyneConvertComponent::Init
bool Init() override
Definition
velodyne_convert_component.cc:29
CYBER_REGISTER_COMPONENT
#define CYBER_REGISTER_COMPONENT(name)
Definition
component.h:656
concurrent_object_pool.h
cyber.h
convert.h
apollo
class register implement
Definition
arena_queue.h:37
apollo::drivers::PointCloud
Definition
pointcloud.proto:14
apollo::drivers::velodyne::VelodyneScan
Definition
velodyne.proto:29
modules
drivers
lidar
velodyne
parser
velodyne_convert_component.h