Apollo  6.0
Open source self driving car software
sensor_object.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 #pragma once
17 
18 #include <memory>
19 #include <string>
20 
21 #include "Eigen/Core"
22 #include "gtest/gtest_prod.h"
23 
27 
28 namespace apollo {
29 namespace perception {
30 namespace fusion {
31 
32 class SensorObject {
33  public:
34  SensorObject() = delete;
35 
36  explicit SensorObject(const std::shared_ptr<const base::Object>& object_ptr);
37 
38  SensorObject(const std::shared_ptr<const base::Object>& object_ptr,
39  const std::shared_ptr<const SensorFrameHeader>& frame_header);
40 
41  SensorObject(const std::shared_ptr<const base::Object>& object_ptr,
42  const std::shared_ptr<SensorFrame>& frame_ptr);
43 
44  // Getter
45  // @brief get frame timestamp which might be different with object timestamp
46  double GetTimestamp() const;
47  bool GetRelatedFramePose(Eigen::Affine3d* pose) const;
48 
49  std::string GetSensorId() const;
51 
52  inline std::shared_ptr<const base::Object> GetBaseObject() const {
53  return object_;
54  }
55 
56  inline double GetInvisiblePeriod() const { return invisible_period_; }
57 
58  inline void SetInvisiblePeriod(double period) { invisible_period_ = period; }
59 
60  private:
61  FRIEND_TEST(SensorObjectTest, test);
62 
63  std::shared_ptr<const base::Object> object_;
64  double invisible_period_ = 0.0;
65  std::shared_ptr<const SensorFrameHeader> frame_header_ = nullptr;
66 };
67 
68 typedef std::shared_ptr<SensorObject> SensorObjectPtr;
69 typedef std::shared_ptr<const SensorObject> SensorObjectConstPtr;
70 
71 class FusedObject {
72  public:
73  FusedObject();
74  ~FusedObject() = default;
75 
76  inline double GetTimestamp() const { return object_->latest_tracked_time; }
77 
78  inline std::shared_ptr<base::Object> GetBaseObject() { return object_; }
79 
80  private:
81  std::shared_ptr<base::Object> object_;
82 };
83 
84 typedef std::shared_ptr<FusedObject> FusedObjectPtr;
85 
86 bool IsLidar(const SensorObjectConstPtr& obj);
87 bool IsRadar(const SensorObjectConstPtr& obj);
88 bool IsCamera(const SensorObjectConstPtr& obj);
89 
90 } // namespace fusion
91 } // namespace perception
92 } // namespace apollo
double GetInvisiblePeriod() const
Definition: sensor_object.h:56
base::SensorType GetSensorType() const
std::shared_ptr< const base::Object > GetBaseObject() const
Definition: sensor_object.h:52
bool IsLidar(const SensorObjectConstPtr &obj)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
double GetTimestamp() const
Definition: sensor_object.h:76
std::shared_ptr< SensorObject > SensorObjectPtr
Definition: sensor_object.h:68
bool IsCamera(const SensorObjectConstPtr &obj)
Definition: sensor_object.h:32
std::shared_ptr< base::Object > GetBaseObject()
Definition: sensor_object.h:78
std::shared_ptr< FusedObject > FusedObjectPtr
Definition: sensor_object.h:84
bool IsRadar(const SensorObjectConstPtr &obj)
Definition: sensor_object.h:71
SensorType
Sensor types are set in the order of lidar, radar, camera, ultrasonic Please make sure SensorType has...
Definition: sensor_meta.h:29
std::shared_ptr< const SensorObject > SensorObjectConstPtr
Definition: sensor_object.h:69
bool GetRelatedFramePose(Eigen::Affine3d *pose) const
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
void SetInvisiblePeriod(double period)
Definition: sensor_object.h:58