Apollo  6.0
Open source self driving car software
velodyne_convert_component.h
Go to the documentation of this file.
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 
31 namespace apollo {
32 namespace drivers {
33 namespace velodyne {
34 
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 
55 
56 } // namespace velodyne
57 } // namespace drivers
58 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
pcl::PointCloud< Point > PointCloud
Definition: types.h:64
Reader subscribes a channel, it has two main functions:
Definition: reader.h:68
bool Proc(const std::shared_ptr< VelodyneScan > &scan_msg) override
Definition: velodyne_convert_component.h:42
Definition: concurrent_object_pool.h:36
#define CYBER_REGISTER_COMPONENT(name)
Definition: component.h:551
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58
apollo::cyber::Writer< T > Writer
Definition: sensor_canbus.h:67