Apollo  6.0
Open source self driving car software
compensator_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 <memory>
20 #include <vector>
21 
23 #include "cyber/cyber.h"
24 
26 
27 namespace apollo {
28 namespace drivers {
29 namespace velodyne {
30 
36 
37 class CompensatorComponent : public Component<PointCloud> {
38  public:
39  bool Init() override;
40  bool Proc(const std::shared_ptr<PointCloud>& point_cloud) override;
41 
42  private:
43  std::unique_ptr<Compensator> compensator_ = nullptr;
44  int pool_size_ = 8;
45  int seq_ = 0;
46  std::shared_ptr<Writer<PointCloud>> writer_ = nullptr;
47  std::shared_ptr<CCObjectPool<PointCloud>> compensator_pool_ = nullptr;
48 };
49 
51 } // namespace velodyne
52 } // namespace drivers
53 } // 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
Definition: compensator_component.h:37
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
bool Proc(const std::shared_ptr< PointCloud > &point_cloud) override