ekf_cal  0.4.0
A Kalman filter-based sensor calibration package
EkfCalNode Class Reference

A ROS2 node for EKF-based sensor calibration. More...

#include <ekf_cal_node.hpp>

Inheritance diagram for EkfCalNode:
[legend]
Collaboration diagram for EkfCalNode:
[legend]

Public Member Functions

 EkfCalNode ()
 Constructor for the Calibration EKF Node.
 
void Initialize ()
 Initialize EKF calibration node.
 
void LoadSensors ()
 Load lists of sensors.
 
void LoadSensorParameters (Sensor::Parameters &params, const std::string &prefix, const std::string &name)
 Load sensor common parameters. More...
 
void LoadImu (const std::string &imu_name)
 Load IMU sensor. More...
 
void LoadCamera (const std::string &camera_name)
 Load camera sensor. More...
 
void LoadGps (const std::string &gps_name)
 Load GPS sensor. More...
 
Eigen::VectorXd LoadProcessNoise ()
 Load process noise. More...
 
IMU::Parameters GetImuParameters (const std::string &imu_name)
 Function for loading IMU parameters. More...
 
Camera::Parameters GetCameraParameters (const std::string &camera_name)
 Function for loading camera parameters. More...
 
GPS::Parameters GetGpsParameters (const std::string &gps_name)
 Function for loading camera parameters. More...
 
void DeclareSensors ()
 Declare parameters for all sensors.
 
void DeclareSensorParameters (const std::string &sensor_name)
 Declare generic sensor parameters. More...
 
void DeclareImuParameters (const std::string &imu_name)
 Declare IMU parameters. More...
 
void DeclareCameraParameters (const std::string &camera_name)
 Declare camera parameters. More...
 
void DeclareTrackerParameters (const std::string &tracker_name)
 Declare tracker parameters. More...
 
void DeclareIntrinsicParameters (const std::string &intrinsics_prefix)
 Declare camera intrinsic parameters. More...
 
void DeclareFiducialParameters (const std::string &fid_name)
 Declare fiducial parameters. More...
 
Intrinsics GetIntrinsicParameters (const std::string &intrinsics_prefix)
 Load camera intrinsic parameters. More...
 
void DeclareGpsParameters (const std::string &gps_name)
 Declare GPS parameters. More...
 
FeatureTracker::Parameters GetTrackerParameters (const std::string &tracker_name)
 Load tracker parameters. More...
 
FiducialTracker::Parameters GetFiducialParameters (const std::string &fiducial_name)
 Load fiducial parameters. More...
 
void ImuCallback (const sensor_msgs::msg::Imu::SharedPtr msg, unsigned int id)
 Callback method for IMU sensor messages. More...
 
void CameraCallback (const sensor_msgs::msg::Image::SharedPtr msg, unsigned int id)
 Callback method for Camera sensor messages. More...
 
void GpsCallback (const sensor_msgs::msg::NavSatFix::SharedPtr msg, unsigned int id)
 Callback method for GPS sensor messages. More...
 
void RegisterImu (std::shared_ptr< RosIMU > imu_ptr, const std::string &topic)
 Register IMU sensor. More...
 
void RegisterCamera (std::shared_ptr< RosCamera > camera_ptr, const std::string &topic)
 Register camera sensor. More...
 
void RegisterGps (std::shared_ptr< RosGPS > gps_ptr, const std::string &topic)
 Register GPS sensor. More...
 
void PublishState ()
 State publisher callback. More...
 

Detailed Description

A ROS2 node for EKF-based sensor calibration.

Todo:

Option to publish health metrics

Option to publish visualization messages

Create generic callback that can be used to store and sort measurements

TF2 Publishing Flag

Option to publish health metrics

Option to publish visualization messages

debug issue with future extrapolation in RVIZ

Member Function Documentation

◆ CameraCallback()

void EkfCalNode::CameraCallback ( const sensor_msgs::msg::Image::SharedPtr  msg,
unsigned int  id 
)

Callback method for Camera sensor messages.

Parameters
msgSensor message pointer
idSensor ID number

◆ DeclareCameraParameters()

void EkfCalNode::DeclareCameraParameters ( const std::string &  camera_name)

Declare camera parameters.

Parameters
camera_nameCamera name

◆ DeclareFiducialParameters()

void EkfCalNode::DeclareFiducialParameters ( const std::string &  fid_name)

Declare fiducial parameters.

Parameters
fid_nameFiducial name

◆ DeclareGpsParameters()

void EkfCalNode::DeclareGpsParameters ( const std::string &  gps_name)

Declare GPS parameters.

Parameters
gps_nameGPS name

◆ DeclareImuParameters()

void EkfCalNode::DeclareImuParameters ( const std::string &  imu_name)

Declare IMU parameters.

Parameters
imu_nameIMU name

◆ DeclareIntrinsicParameters()

void EkfCalNode::DeclareIntrinsicParameters ( const std::string &  intrinsics_prefix)

Declare camera intrinsic parameters.

Parameters
intrinsics_prefixCamera intrinsic prefix

◆ DeclareSensorParameters()

void EkfCalNode::DeclareSensorParameters ( const std::string &  sensor_name)

Declare generic sensor parameters.

Parameters
sensor_nameSensor name

◆ DeclareTrackerParameters()

void EkfCalNode::DeclareTrackerParameters ( const std::string &  tracker_name)

Declare tracker parameters.

Parameters
tracker_nameTracker name

◆ GetCameraParameters()

Camera::Parameters EkfCalNode::GetCameraParameters ( const std::string &  camera_name)

Function for loading camera parameters.

Parameters
camera_nameName of parameter structure
Returns
Camera parameters

◆ GetFiducialParameters()

FiducialTracker::Parameters EkfCalNode::GetFiducialParameters ( const std::string &  fiducial_name)

Load fiducial parameters.

Parameters
fiducial_nameName of parameter structure
Returns
Fiducial parameters

◆ GetGpsParameters()

GPS::Parameters EkfCalNode::GetGpsParameters ( const std::string &  gps_name)

Function for loading camera parameters.

Parameters
gps_nameName of parameter structure
Returns
GPS parameters

◆ GetImuParameters()

IMU::Parameters EkfCalNode::GetImuParameters ( const std::string &  imu_name)

Function for loading IMU parameters.

Parameters
imu_nameName of parameter structure
Returns
IMU parameters

◆ GetIntrinsicParameters()

Intrinsics EkfCalNode::GetIntrinsicParameters ( const std::string &  intrinsics_prefix)

Load camera intrinsic parameters.

Parameters
intrinsics_prefixCamera intrinsic prefix

◆ GetTrackerParameters()

FeatureTracker::Parameters EkfCalNode::GetTrackerParameters ( const std::string &  tracker_name)

Load tracker parameters.

Parameters
tracker_nameName of parameter structure
Returns
Tracker parameters

◆ GpsCallback()

void EkfCalNode::GpsCallback ( const sensor_msgs::msg::NavSatFix::SharedPtr  msg,
unsigned int  id 
)

Callback method for GPS sensor messages.

Parameters
msgSensor message pointer
idSensor ID number

◆ ImuCallback()

void EkfCalNode::ImuCallback ( const sensor_msgs::msg::Imu::SharedPtr  msg,
unsigned int  id 
)

Callback method for IMU sensor messages.

Parameters
msgSensor message pointer
idSensor ID number

◆ LoadCamera()

void EkfCalNode::LoadCamera ( const std::string &  camera_name)

Load camera sensor.

Parameters
camera_nameName of camera to find and load from YAML

◆ LoadGps()

void EkfCalNode::LoadGps ( const std::string &  gps_name)

Load GPS sensor.

Parameters
gps_nameName of GPS to find and load from YAML

◆ LoadImu()

void EkfCalNode::LoadImu ( const std::string &  imu_name)

Load IMU sensor.

Parameters
imu_nameName of IMU to find and load from YAML

◆ LoadProcessNoise()

Eigen::VectorXd EkfCalNode::LoadProcessNoise ( )

Load process noise.

Returns
Process noise vector

◆ LoadSensorParameters()

void EkfCalNode::LoadSensorParameters ( Sensor::Parameters params,
const std::string &  prefix,
const std::string &  name 
)

Load sensor common parameters.

Parameters
paramsParameter struct
prefixSensor parameter prefix
nameSensor name

◆ PublishState()

void EkfCalNode::PublishState ( )

State publisher callback.

Todo:
Copy states before converting to vectors due to race conditions.

◆ RegisterCamera()

void EkfCalNode::RegisterCamera ( std::shared_ptr< RosCamera camera_ptr,
const std::string &  topic 
)

Register camera sensor.

Parameters
camera_ptrCamera sensor shared pointer
topicTopic to subscribe

◆ RegisterGps()

void EkfCalNode::RegisterGps ( std::shared_ptr< RosGPS gps_ptr,
const std::string &  topic 
)

Register GPS sensor.

Parameters
gps_ptrGPS sensor shared pointer
topicTopic to subscribe

◆ RegisterImu()

void EkfCalNode::RegisterImu ( std::shared_ptr< RosIMU imu_ptr,
const std::string &  topic 
)

Register IMU sensor.

Parameters
imu_ptrIMU sensor shared pointer
topicTopic to subscribe

The documentation for this class was generated from the following files: