koide3 / caratheodory2

36 stars 2 forks source link

Implement this approach with g2o framework #4

Open Kenzo2511 opened 8 months ago

Kenzo2511 commented 8 months ago

@koide3 Hi author and everyone, Currently, I am using g2o to optimize graph. But I want to implement this approach (based on the GICP score) to improve the result. I have some questions: 1> When implementing the GICP factor class, what class can I derive from? 2> Does the error function of the GICP factor class return the score between two corresponding point clouds, representing their respective poses? 3> What are the meanings of parameters like H, b, c in the quadratic function within the GICP factor? I hope the author and everyone can help me with the answers. Sincerely.

koide3 commented 8 months ago

Sorry, I have been apart from g2o for a few years, and I'm not sure the exact way to implement the proposed approach with g2o. But, in my case with GTSAM, I implemented a custom GICP registration error factor with gtsam::NonlinearFactor that returns a linearized objective function as gtsam::HessianFactor. The following page explains in detail what do H, b, c (corresponding to G, g, f) in the HessianFactor represent. I hope this helps you.

https://gtsam.org/doxygen/a03764.html

Kenzo2511 commented 8 months ago

Thank you for your answer. You means that I will create a GicpFactor class inherited from gtsam::NonlinearFactor and modify the linearize and error method and returns a gtsam::HessianFactor with H, b, c calculated within the error function (GICP score). Do I need to modify the error method in GicpFactor or inheritance from gtsam::NonlinearFactor? image (3) H corresponds to G, b corresponds to g, and c corresponds to f. Looking forward to hearing from you soon. Thank you very much.

koide3 commented 8 months ago

You are almost correct. You need to GICPFactor that is derived from gtsam::NonlinearFactor. That factor class should override gtsam::NonlinearFactor::linearize to return a gtsam::HessianFactor. Because GICPFactor involves two pose variables, you would need to use this HessianFactor constructor. H, b, and c respectively correspond to G, g, f.

Screenshot_20231225_110343 https://gtsam.org/doxygen/a03764.html#abb07c3bd55ff688700f82f6024bdf9f0

Kenzo2511 commented 8 months ago

Thank you, I understand. However, to ensure the idea, I want to confirm the following two questions: