29 namespace perception {
40 : sensor_info(info), timestamp(ts), sensor2world_pose(pose) {}
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
60 if (pose ==
nullptr) {
61 AERROR <<
"pose is not available";
64 *pose = header_->sensor2world_pose;
69 return foreground_objects_;
73 return foreground_objects_;
77 return background_objects_;
81 return background_objects_;
84 std::string GetSensorId()
const;
91 std::vector<SensorObjectPtr> foreground_objects_;
92 std::vector<SensorObjectPtr> background_objects_;
std::vector< SensorObjectPtr > & GetBackgroundObjects()
Definition: sensor_frame.h:76
SensorFrameHeaderConstPtr GetHeader() const
Definition: sensor_frame.h:88
std::shared_ptr< SensorFrameHeader > SensorFrameHeaderPtr
Definition: base_forward_declaration.h:24
bool GetPose(Eigen::Affine3d *pose) const
Definition: sensor_frame.h:59
double GetTimestamp() const
Definition: sensor_frame.h:57
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: frame_supplement.h:29
std::shared_ptr< Sensor > SensorPtr
Definition: base_forward_declaration.h:32
std::vector< SensorObjectPtr > & GetForegroundObjects()
Definition: sensor_frame.h:68
const std::vector< SensorObjectPtr > & GetBackgroundObjects() const
Definition: sensor_frame.h:80
std::shared_ptr< const Frame > FrameConstPtr
Definition: frame.h:61
const std::vector< SensorObjectPtr > & GetForegroundObjects() const
Definition: sensor_frame.h:72
Definition: frame_supplement.h:46
Definition: sensor_meta.h:57
std::shared_ptr< const SensorFrameHeader > SensorFrameHeaderConstPtr
Definition: base_forward_declaration.h:26
#define AERROR
Definition: log.h:44
SensorType
Sensor types are set in the order of lidar, radar, camera, ultrasonic Please make sure SensorType has...
Definition: sensor_meta.h:29
Definition: sensor_frame.h:45
Definition: frame_supplement.h:55
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
struct apollo::perception::fusion::SensorFrameHeader EIGEN_ALIGN16