pvangoor / eqvio

EqVIO: An Equivariant Filter for Visual Inertial Odometry
GNU General Public License v3.0
81 stars 17 forks source link

Could you grant ros users access to the config file intrinsics.yaml? #4

Closed jingyang-huang closed 6 months ago

jingyang-huang commented 6 months ago

Eqvio is a marvellous work and I have tested it with euroc dataset in asl format. However, when I try to run it with rosbag like this:

./build/eqvio_opt /home/heron/xxx/Codes/ESKF/data/euroc/V1_02_medium/V1_02_medium.bag configs/EQVIO_config_EuRoC_stationary.yaml --display --mode ros

Error message:

No camera intrinsics were not found at
/home/heron/xxx/Codes/ESKF/data/euroc/V1_02_medium/intrinsics.yaml

I've looked through the asl format for.yaml files, but I'm not sure what format intrinsics.yaml is in. Could you please provide me the ros configuration file intrinsics.yaml? That would be really appreciated.

pvangoor commented 6 months ago

Hi Jingyang, I am glad you are enjoying the code. Sorry for this oversight: I had not uploaded this file previously. It should now be fixed as of commit d02dab6. You may have to edit the values in the file to get the right result, however. You will also need to move the file to wherever the code expects it to be. Good luck!

jingyang-huang commented 6 months ago

Thank you pvangoor! I tried the original intrinsics.yaml but it failed, so I modified the readCamera funcion for ros and now it works fine with modified intrinsics.yaml. This is my modified function:

void RosbagDatasetReader::readCamera(const std::string& cameraFileName) {
    YAML::Node cameraFileNode = YAML::LoadFile(cameraFileName);

    // Read the intrinsics
    cv::Size imageSize;
    imageSize.width = cameraFileNode["resolution"][0].as<int>();
    imageSize.height = cameraFileNode["resolution"][1].as<int>();

    cv::Mat K = cv::Mat::eye(3, 3, CV_64F);
    K.at<double>(0, 0) = cameraFileNode["intrinsics"][0].as<double>();
    K.at<double>(1, 1) = cameraFileNode["intrinsics"][1].as<double>();
    K.at<double>(0, 2) = cameraFileNode["intrinsics"][2].as<double>();
    K.at<double>(1, 2) = cameraFileNode["intrinsics"][3].as<double>();

    std::vector<double> distortion;
    distortion = cameraFileNode["distortion_coefficients"].as<std::vector<double>>();

    GIFT::StandardCamera stdCamera = GIFT::StandardCamera(imageSize, K, distortion);
    this->camera = std::make_shared<GIFT::StandardCamera>(stdCamera);
    // camera = std::make_shared<GIFT::StandardCamera>(GIFT::StandardCamera(cv::String(cameraFileName)));

    // Read the extrinsics
    const std::vector<double> extrinsics_entries = cameraFileNode["T_BS"]["data"].as<std::vector<double>>();
    Eigen::Matrix4d extrinsics_matrix(extrinsics_entries.data());
    // The data is in row-major form, but eigen uses column-major by default.
    extrinsics_matrix.transposeInPlace();
    cameraExtrinsics = std::make_unique<liepp::SE3d>(extrinsics_matrix);
}

and this is my intrinsics.yaml intrinsics.yaml.txt , using command: ./build/eqvio_opt /home/heron/xxx/Codes/ESKF/data/euroc/MH_03_medium.bag configs/EQVIO_config_EuRoC_stationary.yaml --display --mode ros the code would work well.

pvangoor commented 6 months ago

I'm glad you got it working, and thanks for working out the fix. Would you mind doing a pull request so I can incorporate your changes?

jingyang-huang commented 6 months ago

I'm glad you got it working, and thanks for working out the fix. Would you mind doing a pull request so I can incorporate your changes?

It`s my pleasure, I would do one pull request in this week.(sorry for the delayed reply as I have an exam to pass)

pvangoor commented 6 months ago

Thanks a lot! Good luck with your exams :)

jingyang-huang commented 6 months ago

Hi pvangoor, I have submitted a pull request recently, would you check and incorporate my changes?