ekf_cal
0.4.0
A Kalman filter-based sensor calibration package
|
#include <camera.hpp>
Classes | |
struct | Parameters |
Camera initialization parameters structure. More... | |
Public Types | |
typedef Camera::Parameters | Parameters |
Camera initialization parameters structure. | |
![]() | |
typedef struct Sensor::Parameters | Parameters |
Sensor parameter structure. | |
Public Member Functions | |
Camera (Camera::Parameters cam_params) | |
Camera sensor constructor. More... | |
void | AddTracker (std::shared_ptr< FeatureTracker > tracker) |
Method to add tracker object to camera sensor. More... | |
void | AddFiducial (std::shared_ptr< FiducialTracker > fiducial) |
Method to add fiducial object to camera sensor. More... | |
void | Callback (std::shared_ptr< CameraMessage > camera_message) |
Callback method for camera. More... | |
![]() | |
Sensor (Parameters params) | |
Sensor class constructor. More... | |
unsigned int | GetId () |
Sensor ID getter method. More... | |
std::string | GetName () |
Sensor name getter method. More... | |
void | Callback (SensorMessage sensor_message) |
Sensor callback function. More... | |
Public Attributes | |
cv::Mat | m_out_img {0, 0, CV_8UC1} |
Published output test image. | |
Protected Member Functions | |
unsigned int | GenerateFrameID () |
Protected Attributes | |
std::shared_ptr< EKF > | m_ekf |
EKF to update. | |
![]() | |
double | m_rate |
Sensor measurement rate. | |
unsigned int | m_id |
Sensor id. | |
std::string | m_name |
Sensor name. | |
std::shared_ptr< DebugLogger > | m_logger |
Debug logger. | |
bool | m_is_initialized {false} |
Sensor initialization flag. | |
|
explicit |
void Camera::AddFiducial | ( | std::shared_ptr< FiducialTracker > | fiducial | ) |
Method to add fiducial object to camera sensor.
fiducial | Fiducial pointer for camera to use during callbacks |
void Camera::AddTracker | ( | std::shared_ptr< FeatureTracker > | tracker | ) |
Method to add tracker object to camera sensor.
tracker | Tracker pointer for camera to use during callbacks |
void Camera::Callback | ( | std::shared_ptr< CameraMessage > | camera_message | ) |
Callback method for camera.
camera_message | camera message |
|
protected |