Apollo  6.0
Open source self driving car software
sensor.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 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 <vector>
23 
24 #include "gtest/gtest_prod.h"
25 
29 
30 namespace apollo {
31 namespace perception {
32 namespace fusion {
33 
34 class Sensor {
35  public:
36  Sensor() = delete;
37 
38  explicit Sensor(const base::SensorInfo& sensor_info)
39  : sensor_info_(sensor_info) {}
40 
41  // query frames whose time stamp is in range
42  // (_latest_fused_time_stamp, time_stamp]
43  void QueryLatestFrames(double timestamp, std::vector<SensorFramePtr>* frames);
44 
45  // query latest frame whose time stamp is in range
46  // (_latest_fused_time_stamp, time_stamp]
47  SensorFramePtr QueryLatestFrame(double timestamp);
48 
49  bool GetPose(double timestamp, Eigen::Affine3d* pose) const;
50 
51  // Getter
52  inline std::string GetSensorId() const { return sensor_info_.name; }
53 
54  // Getter
55  inline base::SensorType GetSensorType() const { return sensor_info_.type; }
56 
57  void AddFrame(const base::FrameConstPtr& frame_ptr);
58 
59  inline static void SetMaxCachedFrameNumber(size_t number) {
60  kMaxCachedFrameNum = number;
61  }
62 
63  void SetLatestQueryTimestamp(const double latest_query_timestamp) {
64  latest_query_timestamp_ = latest_query_timestamp;
65  }
66 
67  private:
68  FRIEND_TEST(SensorTest, test);
69 
70  base::SensorInfo sensor_info_;
71 
72  double latest_query_timestamp_ = 0.0;
73 
74  std::deque<SensorFramePtr> frames_;
75 
76  static size_t kMaxCachedFrameNum;
77 };
78 
79 } // namespace fusion
80 } // namespace perception
81 } // namespace apollo
void AddFrame(const base::FrameConstPtr &frame_ptr)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: sensor.h:34
SensorType type
Definition: sensor_meta.h:59
std::string name
Definition: sensor_meta.h:58
void SetLatestQueryTimestamp(const double latest_query_timestamp)
Definition: sensor.h:63
base::SensorType GetSensorType() const
Definition: sensor.h:55
SensorFramePtr QueryLatestFrame(double timestamp)
std::shared_ptr< const Frame > FrameConstPtr
Definition: frame.h:61
std::shared_ptr< SensorFrame > SensorFramePtr
Definition: base_forward_declaration.h:28
void QueryLatestFrames(double timestamp, std::vector< SensorFramePtr > *frames)
Definition: sensor_meta.h:57
bool GetPose(double timestamp, Eigen::Affine3d *pose) const
SensorType
Sensor types are set in the order of lidar, radar, camera, ultrasonic Please make sure SensorType has...
Definition: sensor_meta.h:29
std::string GetSensorId() const
Definition: sensor.h:52
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
static void SetMaxCachedFrameNumber(size_t number)
Definition: sensor.h:59
Sensor(const base::SensorInfo &sensor_info)
Definition: sensor.h:38