[CMAKE 3] Linking OpenCV, Eigen3, and Pangolin

Sinaenjuni·2023년 7월 13일

CMAKE

목록 보기
3/4

CMakeLists.txt file

cmake_minimum_required(VERSION 3.26)    # Mandatory
project(test1)                  # Mandatory
set(CMAKE_CXX_STANDARD 17)              # Use c++17
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)

add_executable(main main.cpp)

set(OpenCV_DIR "~/thirdparty/OpenCV/install/lib/cmake/opencv4")
find_package(OpenCV REQUIRED)
if (OpenCV_FOUND)
    message(STATUS "OpenCV Found! - ${OpenCV_DIR}")
    message(STATUS "OpenCV Found! - ${OpenCV_INCLUDE_DIRS}")
    message(STATUS "OpenCV Found! - ${OpenCV_LIBS}")
endif()
target_include_directories(main PUBLIC include ${OpenCV_INCLUDE_DIRS})
target_link_libraries(main PUBLIC ${OpenCV_LIBS})

set(Eigen3_DIR "~/thirdparty/Eigen3/install/share/eigen3/cmake")
find_package(Eigen3 REQUIRED)
if (Eigen3_FOUND)
    message(STATUS "Eigen3 Found! - ${Eigen3_DIR}")
    set(Eigen3_LIBS Eigen3::Eigen)    
    # set(Eigen3_INCLUDE_DIRS "~/thirdparty/Eigen3/install/include")

    message(STATUS "Eigen3 Found! - ${Eigen3_INCLUDE_DIRS}")
    message(STATUS "Eigen3 Found! - ${Eigen3_LIBS}")
endif()
target_include_directories(main PUBLIC include ${Eigen3_INCLUDE_DIRS})
target_link_libraries(main PUBLIC ${Eigen3_LIBS})



# # Pangolin 디렉토리의 경로를 Pangolin_SOURCE_DIR 변수에 설정합니다.
# set(Pangolin_SOURCE_DIR "/Users/shinhyeonjun/thirdparty/Pangolin/install")

# # Pangolin_INCLUDE_DIRS 변수에 Pangolin 헤더 파일의 경로를 추가합니다.
# set(Pangolin_INCLUDE_DIRS "${Pangolin_SOURCE_DIR}/include")

# # Pangolin_LIBRARY 변수에 Pangolin 라이브러리 파일의 경로를 추가합니다.
# set(Pangolin_LIBRARY "${Pangolin_SOURCE_DIR}/build/src/libpangolin.so")

# # Pangolin_INCLUDE_DIRS와 Pangolin_LIBRARY 변수를 사용하여 Pangolin을 프로젝트에 추가합니다.
# target_include_directories(main PUBLIC ${Pangolin_INCLUDE_DIRS})
# target_link_libraries(main PUBLIC ${Pangolin_LIBRARY})


set(Pangolin_DIR "/Users/shinhyeonjun/thirdparty/Pangolin_lib/install/lib/cmake/Pangolin")
find_package(Pangolin REQUIRED)
if (Pangolin_FOUND)
    set(Pangolin_INCLUDE_DIRS "/Users/shinhyeonjun/thirdparty/Pangolin_lib/install/include")

    message(STATUS "Pangolin Found! - ${Pangolin_DIR}")
    message(STATUS "Pangolin Found! - ${Pangolin_INCLUDE_DIRS}")
    message(STATUS "Pangolin Found! - ${Pangolin_LIBRARIES}")
endif()
# include_directories(${Pangolin_INCLUDE_DIRS})
target_include_directories(main PUBLIC include ${Pangolin_INCLUDE_DIRS})
target_link_libraries(main PUBLIC ${Pangolin_LIBRARIES})


set(GLEW_DIR "/opt/homebrew/Cellar/glew/2.2.0_1/lib/cmake/")
find_package(GLEW REQUIRED)
# GLEW_INCLUDE_DIRS와 GLEWLIBRARIES 변수를 사용하여 GLEW를 프로젝트에 추가합니다.
target_include_directories(main PRIVATE ${GLEW_INCLUDE_DIRS})
# target_link_libraries(main PRIVATE ${GLEW_LIBRARIES})

# set(Pangolin_DIR "/Users/shinhyeonjun/thirdparty/Pangolin/install")
# find_package(Pangolin REQUIRED)

# if (Pangolin_FOUND) 
#         message(STATUS "Pangolin Found! - ${Pangolin_DIR}")
# endif()

# target_include_directories(main PUBLIC
#         ${Pangolin_INCLUDE_DIRS}
#         )

# target_link_libraries(main PUBLIC
#         ${Pangolin_LIBRARIES}
#         )

Mac을 사용하는 경우

GLEW를 자동으로 연결하지 못해 OpenGL의 Include 부분에서 에러가 날 수 있다. 다음 부분을 추가하면 정상적으로 빌드가 진행된다.

set(GLEW_DIR "/opt/homebrew/Cellar/glew/2.2.0_1/lib/cmake/")
find_package(GLEW REQUIRED)
# GLEW_INCLUDE_DIRS와 GLEWLIBRARIES 변수를 사용하여 GLEW를 프로젝트에 추가합니다.
target_include_directories(main PRIVATE ${GLEW_INCLUDE_DIRS})
# target_link_libraries(main PRIVATE ${GLEW_LIBRARIES})

main.cpp file

데이터와 전체 코드는
https://github.com/gaoxiang12/slambook2/tree/master/ch3/examples
에서 확인할 수 있다.

#include <pangolin/pangolin.h>
#include <Eigen/Core>
#include <unistd.h>

// using namespace std;
// using namespace Eigen;

// path to trajectory file
std::string trajectory_file = "/Users/shinhyeonjun/code/slam/src/trajectory.txt";

void DrawTrajectory(std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d>>);

int main(int argc, char **argv) {

  std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d>> poses;
  std::ifstream fin(trajectory_file);  // txt 파일 읽기
  if (!fin) {
    std::cout << "cannot find trajectory file at " << trajectory_file << std::endl;
    return 1;
  }

// trajectory.txt 파일의 일부
// 1305031526.671473 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 1.000000000
// 1305031526.707547 0.002883195 -0.004662100 -0.002254304 0.011409802 0.010697415 0.002189494 0.999875307
// 1305031526.771481 0.013978966 -0.013082317 -0.010869596 0.043280017 0.032526672 0.003260542 0.998528004
// ...

  while (!fin.eof()) {  // txt 파일의 처음부터 끝까지에 대한 내용을 읽음
    double time, tx, ty, tz, qx, qy, qz, qw;
    fin >> time >> tx >> ty >> tz >> qx >> qy >> qz >> qw; // 공백을 기준으로 한 단어씩 변수로 저장
    Eigen::Isometry3d Twr(Eigen::Quaterniond(qw, qx, qy, qz));
    // Eigen::Quaterniond(qw, qx, qy, qz):
    // 회전을 쿼터니언으로 표현하기 위한 함수
    // qw, qx, qy, qz은 각각 회전에 대한 스칼라값, 회전 벡터 또는 회전 축을 의미
    // Eigen::Isometry3d() <- 선형 변환 행렬과 함께 특정 좌표계에서 다른 좌표계로의 변환을 표현
    //                        3D 공간에서의 이동(translation)과 회전(rotation)을 동시에 표현이 가능
    //                        이동은 3차원 벡터로 표현되며, 회전은 쿼터니언(quaternion)으로 표현
    Twr.pretranslate(Eigen::Vector3d(tx, ty, tz));  // 이동 변환을 수행하는 부분
    poses.push_back(Twr);
  }
  std::cout << "read total " << poses.size() << " pose entries" << std::endl;

  // draw trajectory in pangolin
  DrawTrajectory(poses);
  return 0;
}

/*******************************************************************************************/
void DrawTrajectory(std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d>> poses) {
  // create pangolin window and plot the trajectory
  pangolin::CreateWindowAndBind("Trajectory Viewer", 1024, 768);
  glEnable(GL_DEPTH_TEST);
  glEnable(GL_BLEND);
  glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);

  pangolin::OpenGlRenderState s_cam(
    pangolin::ProjectionMatrix(1024, 768, 500, 500, 512, 389, 0.1, 1000),
    pangolin::ModelViewLookAt(0, -0.1, -1.8, 0, 0, 0, 0.0, -1.0, 0.0)
  );

  pangolin::View &d_cam = pangolin::CreateDisplay()
    .SetBounds(0.0, 1.0, 0.0, 1.0, -1024.0f / 768.0f)
    .SetHandler(new pangolin::Handler3D(s_cam));

  while (pangolin::ShouldQuit() == false) {
    glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
    d_cam.Activate(s_cam);
    glClearColor(1.0f, 1.0f, 1.0f, 1.0f);
    glLineWidth(2);
    for (size_t i = 0; i < poses.size(); i++) {
      Eigen::Vector3d Ow = poses[i].translation();
      Eigen::Vector3d Xw = poses[i] * (0.1 * Eigen::Vector3d(1, 0, 0));
      Eigen::Vector3d Yw = poses[i] * (0.1 * Eigen::Vector3d(0, 1, 0));
      Eigen::Vector3d Zw = poses[i] * (0.1 * Eigen::Vector3d(0, 0, 1));
      glBegin(GL_LINES);
      glColor3f(1.0, 0.0, 0.0);
      glVertex3d(Ow[0], Ow[1], Ow[2]);
      glVertex3d(Xw[0], Xw[1], Xw[2]);
      glColor3f(0.0, 1.0, 0.0);
      glVertex3d(Ow[0], Ow[1], Ow[2]);
      glVertex3d(Yw[0], Yw[1], Yw[2]);
      glColor3f(0.0, 0.0, 1.0);
      glVertex3d(Ow[0], Ow[1], Ow[2]);
      glVertex3d(Zw[0], Zw[1], Zw[2]);
      glEnd();
    }
    for (size_t i = 0; i < poses.size(); i++) {
      glColor3f(0.0, 0.0, 0.0);
      glBegin(GL_LINES);
      auto p1 = poses[i], p2 = poses[i + 1];
      glVertex3d(p1.translation()[0], p1.translation()[1], p1.translation()[2]);
      glVertex3d(p2.translation()[0], p2.translation()[1], p2.translation()[2]);
      glEnd();
    }
    pangolin::FinishFrame();
    usleep(5000);   // sleep 5 ms
  }
}

0개의 댓글