22 #include "gtest/gtest_prod.h" 29 namespace perception {
36 explicit SensorObject(
const std::shared_ptr<const base::Object>& object_ptr);
38 SensorObject(
const std::shared_ptr<const base::Object>& object_ptr,
39 const std::shared_ptr<const SensorFrameHeader>& frame_header);
41 SensorObject(
const std::shared_ptr<const base::Object>& object_ptr,
42 const std::shared_ptr<SensorFrame>& frame_ptr);
61 FRIEND_TEST(SensorObjectTest, test);
63 std::shared_ptr<const base::Object> object_;
64 double invisible_period_ = 0.0;
65 std::shared_ptr<const SensorFrameHeader> frame_header_ =
nullptr;
76 inline double GetTimestamp()
const {
return object_->latest_tracked_time; }
78 inline std::shared_ptr<base::Object>
GetBaseObject() {
return object_; }
81 std::shared_ptr<base::Object> object_;
86 bool IsLidar(
const SensorObjectConstPtr& obj);
87 bool IsRadar(
const SensorObjectConstPtr& obj);
88 bool IsCamera(
const SensorObjectConstPtr& obj);
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
std::string GetSensorId() const
double GetTimestamp() const
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