66 Eigen::Vector3d *point3d)
const {
73 Eigen::Vector4d *plane_param)
const {
100 const std::map<std::string, float> &name_camera_ground_height_map,
101 const std::map<std::string, float> &name_camera_pitch_angle_diff_map,
102 const float &pitch_angle_master_sensor) {
106 virtual std::string
Name()
const = 0;
112#define REGISTER_CALIBRATION_SERVICE(name) \
113 PERCEPTION_REGISTER_CLASS(BaseCalibrationService, name)
DISALLOW_COPY_AND_ASSIGN(BaseCalibrationService)
virtual float QueryCameraToGroundHeight() const
virtual bool QueryDepthOnGroundPlane(int x, int y, double *depth) const
virtual std::string Name() const =0
virtual void Update(onboard::CameraFrame *frame)
virtual bool QueryPoint3dOnGroundPlane(int x, int y, Eigen::Vector3d *point3d) const
virtual ~BaseCalibrationService()=default
BaseCalibrationService()=default
virtual bool Init(const CalibrationServiceInitOptions &options=CalibrationServiceInitOptions())=0
virtual bool QueryCameraToWorldPose(Eigen::Matrix4d *pose) const
virtual bool BuildIndex()=0
virtual bool QueryCameraToGroundHeightAndPitchAngle(float *height, float *pitch) const
virtual void Update(CameraFrame *frame)
virtual void SetCameraHeightAndPitch(const std::map< std::string, float > &name_camera_ground_height_map, const std::map< std::string, float > &name_camera_pitch_angle_diff_map, const float &pitch_angle_master_sensor)
virtual bool QueryGroundPlaneInCameraFrame(Eigen::Vector4d *plane_param) const
virtual float QueryPitchAngle() const
std::map< T, EigenType, std::less< T >, Eigen::aligned_allocator< std::pair< const T, EigenType > > > EigenMap
#define PERCEPTION_REGISTER_REGISTERER(base_class)
std::string calibrator_method
std::string calibrator_working_sensor_name
apollo::common::EigenMap< std::string, Eigen::Matrix3f > name_intrinsic_map