GTSAM 튜토리얼

Pose Graph Optimization (PGO) for SLAM

2023-07-15

서론:


그래서 해당 포스트에서는


1. 예제 코드

////// GTSAM headers
#include <gtsam/geometry/Rot3.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/ISAM2.h>

using namespace std;

////// GTSAM variables
shared_ptr<gtsam::ISAM2> m_isam_handler = nullptr;
gtsam::NonlinearFactorGraph m_gtsam_graph;
gtsam::Values m_init_esti; // initial estimation (초기 위치 추정치)
gtsam::Values m_corrected_esti; //Graph optimized된 보정된 위치 추정치
int m_keyframe_index = 0;

////// GTSAM init
gtsam::ISAM2Params isam_params_;
isam_params_.relinearizeThreshold = 0.01;
isam_params_.relinearizeSkip = 1;
m_isam_handler = std::make_shared<gtsam::ISAM2>(isam_params_);

////// Odometry callback function
void odometry_callback_function(current_odometry) //실제 함수 아님, pseudo code
{
  if (!initialized) // 최초 1회만 odometry를 Priorfactor로 추가
  {
    gtsam::noiseModel::Diagonal::shared_ptr prior_noise = gtsam::noiseModel::Diagonal::Variances((gtsam::Vector(6) << 1e-4, 1e-4, 1e-4, 1e-4, 1e-4, 1e-4).finished()); // rad*rad for roll, pitch, yaw and meter*meter for x, y, z
    // for the first odometry, priorfactor
    m_gtsam_graph.add(gtsam::PriorFactor<gtsam::Pose3>(0, odometry_to_gtsam_pose(current_odometry), prior_noise));
    m_init_esti.insert(m_current_keyframe_idx, odometry_to_gtsam_pose(current_odometry));
    m_keyframe_index++;
    initialized = true;
  }
  else //그 이후 odometry callback 마다
  {
    if (if_keyframe_or_not(current_odometry)) //keyframe인지 검사하고 keyframe이면
    {
      ///// 1. keyframe사이의 pose 변화를 graph에 추가
      gtsam::noiseModel::Diagonal::shared_ptr odom_noise = gtsam::noiseModel::Diagonal::Variances((gtsam::Vector(6) << 1e-4, 1e-4, 1e-4, 1e-2, 1e-2, 1e-2).finished());
      gtsam::Pose3 pose_from = odometry_to_gtsam_pose(last_odometry);
      gtsam::Pose3 pose_to = odometry_to_gtsam_pose(current_odometry);
      // 직전, 현재 keyframe odometry 사이의 odometry 변화값을 BetweenFactor로 그래프에 추가
      m_gtsam_graph.add(gtsam::BetweenFactor<gtsam::Pose3>(m_keyframe_index-1, m_keyframe_index, pose_from.between(pose_to), odom_noise));
      m_init_esti.insert(m_keyframe_index, pose_to);
      m_keyframe_index++;
      last_odometry = current_odometry; //다음 iteration을 위해 직전 odometry 저장

      ///// 2. loop closing factor
      bool if_loop_closed = false;
      // 과거의 keyframe들과 현재 keyframe을 비교해서, loop closing이 
      // 일어날 수 있을 가능성이 있는지 파악 (예: 일정 거리 이내에 있으나 시간이 일정 시간 이상 경과)
      if (if_loop_candidate_or_not(current_odometry))
      {
        //가장 loop 가능성이 높은 keyframe 반환
        the_most_loop_likely_keyframe = get_the_most_loop_likely_keyframe(current_odometry);
        //현재 keyframe, loop 가능성 높은 keyframe 사이를 매칭해서 pose 변환 반환 (e.g., ICP 등)
        loop_match_result = loop_matching(current_odometry, the_most_loop_likely_keyframe);

        // 실제로 loop-closed 되었으면
        if (loop_match_result.loop_closed)
        {
          noise = loop_match_result.noise;
          loop_pose_tf = loop_match_result.pose_transformation;
          past_pose = the_most_loop_likely_keyframe.pose;
          past_pose_index = the_most_loop_likely_keyframe.pose.index;
          current_odometry_index = m_keyframe_index-1; // becaus of ++ from the above line

          // 현재 keyframe과 loop-closed 된 keyframe간의
          // pose 변화만큼을 graph에 BetweenFactor로 추가
          gtsam::noiseModel::Diagonal::shared_ptr loop_noise = gtsam::noiseModel::Diagonal::Variances((gtsam::Vector(6) << noise, noise, noise, noise, noise, noise).finished());
          gtsam::Pose3 pose_from = odometry_to_gtsam_pose(loop_pose_tf * current_odometry);
          gtsam::Pose3 pose_to = odometry_to_gtsam_pose(past_pose);
          m_gtsam_graph.add(gtsam::BetweenFactor<gtsam::Pose3>(current_odometry_index, past_pose_index, pose_from.between(pose_to), loop_noise));	    		
          if_loop_closed = true;
        }
      }

      ///// 3. Optimize
      //m_corrected_esti = gtsam::LevenbergMarquardtOptimizer(m_gtsam_graph, m_init_esti).optimize();
      m_isam_handler->update(m_gtsam_graph, m_init_esti);
      m_isam_handler->update();
      if (if_loop_closed)
      {
        m_isam_handler->update();
        m_isam_handler->update();
        m_isam_handler->update();
      }
      m_gtsam_graph.resize(0);
      m_init_esti.clear();
      // 보정된 위치 추정치
      m_corrected_esti = m_isam_handler->calculateEstimate();
    }
  }
}


GTSAM PGO

처음 보는 사람들은, 대충 알긴 알겠는데 몇 가지 “왜?” 하는 부분들이 생긴다 => 뒤에서 하나씩 설명한다.


2. Factor vs Values in GTSAM

GTSAM PGO


3. gtsam::ISAM2.update vs gtsam::LevenbergMarquardtOptimizer

//// 이 한 줄이랑
{
  m_corrected_esti = gtsam::LevenbergMarquardtOptimizer(m_gtsam_graph, m_init_esti).optimize();
}
//// 이 여러 줄이랑 같은 역할임
{
  m_isam_handler->update(m_gtsam_graph, m_init_esti);
  m_gtsam_graph.resize(0);
  m_init_esti.clear();
  m_corrected_esti = m_isam_handler->calculateEstimate();  
}


4. gtsam::ISAM2.update(graph, initial_estimation) vs gtsam::ISAM2.update()

m_isam_handler->update(m_gtsam_graph, m_init_esti); //한 번 했는데
m_isam_handler->update(); //여러 번 인자도 없이 반복한다.
if (if_loop_closed) //심지어 loop-closing 되면
{
  m_isam_handler->update(); //인자도 없이 또 반복한다.
  m_isam_handler->update(); //인자도 없이 또또 반복한다.
  m_isam_handler->update(); //인자도 없이 또또또 반복한다.
}


5. 참고


결론 및 추가 정보