21 #include <unordered_map> 24 #include "gtest/gtest_prod.h" 33 namespace perception {
50 std::vector<SensorFramePtr>* frames)
const;
53 std::vector<SensorFramePtr>* frames)
const;
55 bool GetPose(
const std::string& sensor_id,
double timestamp,
59 const std::string& sensor_id)
const;
63 std::unordered_map<std::string, SensorPtr> sensors_;
67 FRIEND_TEST(SensorDataManagerTest, test);
base::BaseCameraModelPtr GetCameraIntrinsic(const std::string &sensor_id) const
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void GetLatestFrames(double timestamp, std::vector< SensorFramePtr > *frames) const
bool IsLidar(const base::FrameConstPtr &frame_ptr)
Definition: sensor_data_manager.h:36
bool GetPose(const std::string &sensor_id, double timestamp, Eigen::Affine3d *pose) const
#define DECLARE_SINGLETON(classname)
Definition: macros.h:52
std::shared_ptr< const Frame > FrameConstPtr
Definition: frame.h:61
bool IsRadar(const base::FrameConstPtr &frame_ptr)
void GetLatestSensorFrames(double timestamp, const std::string &sensor_id, std::vector< SensorFramePtr > *frames) const
Definition: sensor_manager.h:35
bool IsCamera(const base::FrameConstPtr &frame_ptr)
std::shared_ptr< BaseCameraModel > BaseCameraModelPtr
Definition: camera.h:75
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
void AddSensorMeasurements(const base::FrameConstPtr &frame_ptr)