Apollo  6.0
Open source self driving car software
online_visualizer_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 
22 #pragma once
23 
24 #include <memory>
25 #include <string>
26 #include <vector>
27 
28 #include "glog/logging.h"
29 #include "gtest/gtest_prod.h"
30 
31 #include "cyber/cyber.h"
32 
33 #include "modules/drivers/proto/pointcloud.pb.h"
34 #include "modules/localization/proto/localization.pb.h"
35 
39 
44 namespace apollo {
45 namespace localization {
46 namespace msf {
47 
49  : public cyber::Component<drivers::PointCloud> {
50  public:
53 
58  bool Init() override;
59 
60  bool Proc(const std::shared_ptr<drivers::PointCloud> &msg) override;
61 
62  private:
63  bool InitConfig();
64  bool InitIO();
65  void OnLidarLocalization(
66  const std::shared_ptr<LocalizationEstimate> &message);
67  void OnGNSSLocalization(const std::shared_ptr<LocalizationEstimate> &message);
68  void OnFusionLocalization(
69  const std::shared_ptr<LocalizationEstimate> &message);
70 
71  void ParsePointCloudMessage(
72  const std::shared_ptr<drivers::PointCloud> &message,
74  std::vector<unsigned char> *intensities);
75 
76  private:
77  std::string lidar_extrinsic_file_;
78  std::string map_folder_;
79  std::string map_visual_folder_;
80 
81  std::shared_ptr<cyber::Reader<LocalizationEstimate>> lidar_local_listener_ =
82  nullptr;
83  std::string lidar_local_topic_ = "";
84 
85  std::shared_ptr<cyber::Reader<LocalizationEstimate>> gnss_local_listener_ =
86  nullptr;
87  std::string gnss_local_topic_ = "";
88 
89  std::shared_ptr<cyber::Reader<LocalizationEstimate>> fusion_local_listener_ =
90  nullptr;
91  std::string fusion_local_topic_ = "";
92 
93  std::shared_ptr<cyber::Reader<LocalizationEstimate>> ndt_local_listener_ =
94  nullptr;
95  std::string ndt_local_topic_ = "";
96 };
97 
99 
100 } // namespace msf
101 } // namespace localization
102 } // namespace apollo
bool Proc(const std::shared_ptr< drivers::PointCloud > &msg) override
Definition: online_visualizer_component.h:48
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
CYBER_REGISTER_COMPONENT(OnlineVisualizerComponent)
bool Init() override
module initialization function
EigenVector< Eigen::Vector3d > EigenVector3dVec
Definition: eigen_defs.h:38
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58