29 namespace perception {
39 const Eigen::Affine3d& pose)
40 : sensor_info(info), timestamp(ts), sensor2world_pose(pose) {}
57 inline bool GetPose(Eigen::Affine3d* pose)
const {
58 if (pose ==
nullptr) {
59 AERROR <<
"pose is not available";
62 *pose = header_->sensor2world_pose;
67 return foreground_objects_;
71 return foreground_objects_;
75 return background_objects_;
79 return background_objects_;
82 std::string GetSensorId()
const;
89 std::vector<SensorObjectPtr> foreground_objects_;
90 std::vector<SensorObjectPtr> background_objects_;
std::vector< SensorObjectPtr > & GetBackgroundObjects()
Definition: sensor_frame.h:74
SensorFrameHeaderConstPtr GetHeader() const
Definition: sensor_frame.h:86
std::shared_ptr< SensorFrameHeader > SensorFrameHeaderPtr
Definition: base_forward_declaration.h:24
bool GetPose(Eigen::Affine3d *pose) const
Definition: sensor_frame.h:57
double GetTimestamp() const
Definition: sensor_frame.h:55
Definition: frame_supplement.h:29
std::shared_ptr< Sensor > SensorPtr
Definition: base_forward_declaration.h:32
std::vector< SensorObjectPtr > & GetForegroundObjects()
Definition: sensor_frame.h:66
const std::vector< SensorObjectPtr > & GetBackgroundObjects() const
Definition: sensor_frame.h:78
std::shared_ptr< const Frame > FrameConstPtr
Definition: frame.h:59
const std::vector< SensorObjectPtr > & GetForegroundObjects() const
Definition: sensor_frame.h:70
Definition: frame_supplement.h:46
Definition: sensor_meta.h:57
std::shared_ptr< const SensorFrameHeader > SensorFrameHeaderConstPtr
Definition: base_forward_declaration.h:26
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:43
Definition: frame_supplement.h:55