VisualSLAM 2

国立研究開発法人産業技術総合研究所がGitHubで公開していた方のOpenVSLAMへの入力にRealSense D455を使い地図を作成します。

(2022年3月までは下記の手順で環境を構築できたのですが、OpenVSLAM Communityの方も閉じたので、今はこの手順で環境構築できなくなってしまいました。(2022.04.15))

こちらになったようです。
stella-cv

最初は単眼カメラとして

RealSense D455はRGB-D CameraなのでDenseなMapを作ることが出来ることに期待なのですが、最初は、取得したRGBのみを使って動かします。

Ubuntu

もうgit cloneは出来ないので、何かしらの方法でNUCのUbuntu 20.04にopenvslamを渡します。
オリジナルを保存しておきます。


$ cd ~/develop
$ cp -r openvslam openvslam_original

元々git管理されていたものなので差分はgit diffで確認できます。


$ cd openvslam
$ ctags -R

impl

Intelが用意してくれているので、移植します。


$ vi -O example/run_camera_slam.cc ../100_sift/sift.cpp
$ vi -O example/run_camera_slam.cc ../wrap/opencv/dnn/rs-dnn.cpp
$ vi -O example/run_camera_slam.cc ../wrap/opencv/grabcuts/rs-grabcuts.cpp

変更したものがこちら。

run_camera_slam.cc

#define USE_PANGOLIN_VIEWER

#include </usr/include/GL/glew.h>

#ifdef USE_PANGOLIN_VIEWER
#include "pangolin_viewer/viewer.h"
#elif USE_SOCKET_PUBLISHER
#include "socket_publisher/publisher.h"
#endif

#include "openvslam/system.h"
#include "openvslam/config.h"
#include "openvslam/util/stereo_rectifier.h"

#include <iostream>
#include <chrono>
#include <numeric>

#include <opencv2/core/core.hpp>
#include <opencv2/imgcodecs.hpp>
#include <opencv2/imgproc.hpp>
// #include <opencv2/videoio.hpp>
#include <spdlog/spdlog.h>
#include <popl.hpp>

#ifdef USE_STACK_TRACE_LOGGER
#include <glog/logging.h>
#endif

#ifdef USE_GOOGLE_PERFTOOLS
#include <gperftools/profiler.h>
#endif

// -----------------------------------------------------------------------------

#include <iostream>
#include <algorithm>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/thread/thread.hpp>
#include <string>

// Intel Realsense Headers
#include <librealsense2/rs.hpp> // Include RealSense Cross Platform API

#include <cv-helpers.hpp>
#include <opencv2/opencv.hpp>   // Include OpenCV API

using namespace std;

// -----------------------------------------------------------------------------

void mono_tracking(const std::shared_ptr<openvslam::config>& cfg,
                   const std::string& vocab_file_path, const unsigned int cam_num, const std::string& mask_img_path,
                   const float scale, const std::string& map_db_path) {
    // load the mask image
    const cv::Mat mask = mask_img_path.empty() ? cv::Mat{} : cv::imread(mask_img_path, cv::IMREAD_GRAYSCALE);

    // build a SLAM system
    openvslam::system SLAM(cfg, vocab_file_path);
    // startup the SLAM process
    SLAM.startup();

    // create a viewer object
    // and pass the frame_publisher and the map_publisher
#ifdef USE_PANGOLIN_VIEWER
    pangolin_viewer::viewer viewer(cfg, &SLAM, SLAM.get_frame_publisher(), SLAM.get_map_publisher());
#elif USE_SOCKET_PUBLISHER
    socket_publisher::publisher publisher(cfg, &SLAM, SLAM.get_frame_publisher(), SLAM.get_map_publisher());
#endif

    rs2::pipeline pipe;
    // rs2::config cfg;
    rs2::config rs2_cfg;
    // cfg.enable_stream(RS2_STREAM_COLOR);
    // cfg.enable_stream(RS2_STREAM_INFRARED);
    // cfg.enable_stream(RS2_STREAM_DEPTH);
    rs2_cfg.enable_stream(RS2_STREAM_COLOR);
    // rs2_cfg.enable_stream(RS2_STREAM_INFRARED);
    // rs2_cfg.enable_stream(RS2_STREAM_DEPTH);
    // rs2::pipeline_profile selection = pipe.start(cfg);
    rs2::pipeline_profile selection = pipe.start(rs2_cfg);
    rs2::device selected_device = selection.get_device();
    // auto depth_sensor = selected_device.first<rs2::depth_sensor>();

    // if (depth_sensor.supports(RS2_OPTION_EMITTER_ENABLED))
    // {
    //     depth_sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 1.f); // Enable emitter
    //     pipe.wait_for_frames();
    //     depth_sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 0.f); // Disable emitter
    // }
    // if (depth_sensor.supports(RS2_OPTION_LASER_POWER))
    // {
    //     // Query min and max values:
    //     auto range = depth_sensor.get_option_range(RS2_OPTION_LASER_POWER);
    //     depth_sensor.set_option(RS2_OPTION_LASER_POWER, range.max); // Set max power
    //     sleep(1);
    //     depth_sensor.set_option(RS2_OPTION_LASER_POWER, 0.f); // Disable laser
    // }
    rs2::align align_to(RS2_STREAM_COLOR);
    // auto video = cv::VideoCapture(cam_num);
    // if (!video.isOpened()) {
    //     spdlog::critical("cannot open a camera {}", cam_num);
    //     SLAM.shutdown();
    //     return;
    // }

    cv::Mat frame;
    double timestamp = 0.0;
    std::vector<double> track_times;

    unsigned int num_frame = 0;

    bool is_not_end = true;

    // run the SLAM in another thread
    std::thread thread([&]() {
        while (is_not_end) {
            // check if the termination of SLAM system is requested or not
            if (SLAM.terminate_is_requested()) {
                break;
            }

            auto frames = pipe.wait_for_frames();
            // auto color_frame = frames.get_color_frame();
            // auto depth = frames.get_depth_frame();
            // auto RGB = frames.get_color_frame();
            // is_not_end = video.read(frame);

            auto aligned_set = align_to.process(frames);
            auto color_frame = aligned_set.get_color_frame();
            // auto depth_frame = aligned_set.get_depth_frame();

            /// get cv::Mat format
            frame = frame_to_mat(color_frame);
            // auto color_mat = frame_to_mat(color_frame);
            // auto depth_mat = depth_frame_to_meters(depth_frame);

            if (frame.empty()) {
                std::cout << "empty" << std::endl;
                continue;
            }
            // if (scale != 1.0) {
            //     cv::resize(frame, frame, cv::Size(), scale, scale, cv::INTER_LINEAR);
            // }

            /// euroc mono
            cv::resize(frame, frame, cv::Size(752, 480), 0, 0, cv::INTER_LINEAR);

            const auto tp_1 = std::chrono::steady_clock::now();

            // input the current frame and estimate the camera pose
            SLAM.feed_monocular_frame(frame, timestamp, mask);

            const auto tp_2 = std::chrono::steady_clock::now();

            const auto track_time = std::chrono::duration_cast<std::chrono::duration<double>>(tp_2 - tp_1).count();
            track_times.push_back(track_time);

            timestamp += 1.0 / cfg->camera_->fps_;
            ++num_frame;
        }

        // wait until the loop BA is finished
        while (SLAM.loop_BA_is_running()) {
            std::this_thread::sleep_for(std::chrono::microseconds(5000));
        }
    });

    // run the viewer in the current thread
#ifdef USE_PANGOLIN_VIEWER
    viewer.run();
#elif USE_SOCKET_PUBLISHER
    publisher.run();
#endif

    thread.join();

    // shutdown the SLAM process
    SLAM.shutdown();

    if (!map_db_path.empty()) {
        // output the map database
        SLAM.save_map_database(map_db_path);
    }

    std::sort(track_times.begin(), track_times.end());
    const auto total_track_time = std::accumulate(track_times.begin(), track_times.end(), 0.0);
    std::cout << "median tracking time: " << track_times.at(track_times.size() / 2) << "[s]" << std::endl;
    std::cout << "mean tracking time: " << total_track_time / track_times.size() << "[s]" << std::endl;
}

単眼カメラを使いたいので、mono_tracking()の中を変えています。
stereo_trackingの方のVideoCapture関連のみ、コンパイラを黙らせるためにコメントアウトしています。他は変更していません。

build

buildするのでexampleに移動します。


$ cd example

勿論、下記から始めてもいいです。cmakeが用意されているので、こちらが普通と思います。


$ cd ~/develop/openvslam
$ mkdir build
$ cd build
$ cmake ..

cmakeのことは忘れて、作業を続けます。
ここでは、未だ上記のソースコードに変更していないとします。


$ g++ run_camera_slam.cc -o SLAM

怒られます。


run_camera_slam.cc:7:10: fatal error: openvslam/system.h: No such file or directory
    7 | #include "openvslam/system.h"
      |          ^~~~~~~~~~~~~~~~~~~~
compilation terminated.

$ g++ run_camera_slam.cc -I ../src -o SLAM

怒られます。


In file included from ../src/openvslam/system.h:4,
                 from run_camera_slam.cc:7:
../src/openvslam/type.h:10:10: fatal error: Eigen/Core: No such file or directory
   10 | #include <Eigen/Core>
      |          ^~~~~~~~~~~~
compilation terminated.

この環境はPCLを使うために過去に下記を実行しています。そのときにEigenもインストールされています。


$ sudo apt install libpcl-dev

下記は不要です。


$ sudo apt install libeigen3-dev

$ g++ run_camera_slam.cc -I ../src -I /usr/include/eigen3 -o SLAM

怒られます。OpenCVが無い、と。


In file included from ../src/openvslam/system.h:4,
                 from run_camera_slam.cc:7:
../src/openvslam/type.h:12:10: fatal error: opencv2/core/types.hpp: No such file or directory
   12 | #include <opencv2/core/types.hpp>
      |          ^~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.

OpenCV4.2がインストールされます。(2022.03.10)


$ sudo apt install libopencv-dev

$ g++ run_camera_slam.cc -I ../src -I /usr/include/eigen3 -I /usr/include/opencv4 -o SLAM

怒られます。Fast Bag of Wordsが無い、と。


In file included from ../src/openvslam/system.h:5,
                 from run_camera_slam.cc:7:
../src/openvslam/data/bow_vocabulary.h:8:10: fatal error: fbow/fbow.h: No such file or directory
    8 | #include <fbow/fbow.h>
      |          ^~~~~~~~~~~~~
compilation terminated.

FBoWはOpenVSLAM Communityによるカスタムバージョンを使ってくれ、と書いてあります。
ここはcmakeを使うことにします。


$ sudo apt install cmake

こちらは公開されています。


$ cd ~/develop
$ git clone https://github.com/OpenVSLAM-Community/FBoW.git
$ cd FBoW
$ mkdir build
$ cd build
$ cmake ..
$ make -j2

~/.bashrcを編集してLIBRARY_PATHに上記を付け加えます。


$ vi ~/.bashrc

.bashrc

LIBRARY_PATH=/home/jn/develop/vcpkg/packages/realsense2_x64-linux/lib:$LIBRARY_PATH
LIBRARY_PATH=/home/jn/develop/vcpkg/packages/libusb_x64-linux/lib:$LIBRARY_PATH
LIBRARY_PATH=/usr/lib/x86_64-linux-gnu:$LIBRARY_PATH
LIBRARY_PATH=/home/jn/develop/FBoW/build:$LIBRARY_PATH
export LIBRARY_PATH

読み込みます。


$ . ~/.bashrc

$ g++ run_camera_slam.cc -I ../src -I /usr/include/eigen3 -I /usr/include/opencv4 -I ../../FBoW/include -o SLAM

yaml-cppが無いと怒られます。


In file included from ../src/openvslam/config.h:4,
                 from run_camera_slam.cc:8:
../src/openvslam/camera/base.h:10:10: fatal error: yaml-cpp/yaml.h: No such file or directory
   10 | #include <yaml-cpp/yaml.h>
      |          ^~~~~~~~~~~~~~~~~
compilation terminated.

$ sudo apt install libyaml-cpp-dev

$ g++ run_camera_slam.cc -I ../src -I /usr/include/eigen3 -I /usr/include/opencv4 -I ../../FBoW/include -o SLAM

nlohmann-json3が無いと怒られます。


In file included from ../src/openvslam/config.h:4,
                 from run_camera_slam.cc:8:
../src/openvslam/camera/base.h:11:10: fatal error: nlohmann/json_fwd.hpp: No such file or directory
   11 | #include <nlohmann/json_fwd.hpp>
      |          ^~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.

$ sudo apt install nlohmann-json3-dev

$ g++ run_camera_slam.cc -I ../src -I /usr/include/eigen3 -I /usr/include/opencv4 -I ../../FBoW/include -o SLAM

spdlogが無いと怒られます。


run_camera_slam.cc:19:10: fatal error: spdlog/spdlog.h: No such file or directory
   19 | #include <spdlog/spdlog.h>
      |          ^~~~~~~~~~~~~~~~~
compilation terminated.

$ sudo apt install libspdlog-dev

$ g++ run_camera_slam.cc -I ../src -I /usr/include/eigen3 -I /usr/include/opencv4 -I ../../FBoW/include -o SLAM

poplが無いと怒られます。openvslamのgit cloneの中に入っているのでこれを使います。


$ g++ run_camera_slam.cc -I ../src -I /usr/include/eigen3 -I /usr/include/opencv4 -I ../../FBoW/include -I ../3rd/popl/include -o SLAM

これでコンパイルは通りますが、リンクで滅茶苦茶に怒られます。

ここからはMakefileを使います。完成品です。

Makefile

CC = g++
CFLAGS = -O2
BIN = SLAM
INC = -I ../src -I /usr/include/eigen3 -I /usr/include/opencv4 -I ../../FBoW/include -I ../3rd/popl/include -I /usr/include/suitesparse
INCRS = -I /home/jn/develop/wrap/opencv -I /usr/include/vtk-7.1
LIB = -l realsense2 -l fw -l realsense-file -l usb-1.0 -l pthread -l udev -l boost_filesystem
LIB1 = -l GL -l glfw -l GLU -l GLEW
# LIBPCL = -l pcl_common -l pcl_filters -l pcl_io -l pcl_visualization -l pcl_search -l pcl_outofcore -l pcl_octree
# LIBVTK = -l vtkCommonCore-7.1 -l vtkCommonDataModel-7.1 -l vtkCommonMath-7.1 -l vtkRenderingCore-7.1
LIB2 = -l opencv_core -l opencv_imgcodecs -l opencv_imgproc -l opencv_features2d -l opencv_calib3d -l yaml-cpp -l opencv_highgui
LIB3 = -l g2o_core -l g2o_stuff -l g2o_types_sba -l g2o_types_sim3 -l g2o_solver_dense -l g2o_solver_eigen -l g2o_solver_csparse -l g2o_csparse_extension -l gomp -l cxsparse -l glog
LIB4 = -l fbow -l pango_core -l pango_display -l pango_plot -l pango_tools -l pango_vars -l pango_opengl

OBJS = run_camera_slam.o \
	   system.o \
	   tracking_module.o \
	   mapping_module.o \
	   config.o \
	   global_optimization_module.o \
	   base.o \
	   equirectangular.o \
	   fisheye.o \
	   perspective.o \
	   bow_database.o \
	   camera_database.o \
	   common.o \
	   frame.o \
	   frame_statistics.o \
	   graph_node.o \
	   keyframe.o \
	   landmark.o \
	   map_database.o \
	   orb_extractor.o \
	   orb_extractor_node.o \
	   orb_params.o \
	   init_base.o \
	   bearing_vector.o \
	   init_perspective.o \
	   map_database_io.o \
	   trajectory_io.o \
	   area.o \
	   bow_tree.o \
	   fuse.o \
	   projection.o \
	   robust.o \
	   stereo.o \
	   frame_tracker.o \
	   initializer.o \
	   keyframe_inserter.o \
	   local_map_cleaner.o \
	   loop_bundle_adjuster.o \
	   loop_detector.o \
	   relocalizer.o \
	   two_view_triangulator.o \
	   global_bundle_adjuster.o \
	   graph_optimizer.o \
	   local_bundle_adjuster.o \
	   pose_optimizer.o \
	   transform_optimizer.o \
	   landmark_vertex.o \
	   landmark_vertex_container.o \
	   equirectangular_pose_opt_edge.o \
	   equirectangular_reproj_edge.o \
	   perspective_pose_opt_edge.o \
	   perspective_reproj_edge.o \
	   se3_shot_vertex.o \
	   shot_vertex_container.o \
	   backward_reproj_edge.o \
	   forward_reproj_edge.o \
	   graph_opt_edge.o \
	   sim3_shot_vertex.o \
	   transform_vertex.o \
	   frame_publisher.o \
	   map_publisher.o \
	   solve_common.o \
	   essential_solver.o \
	   fundamental_solver.o \
	   homography_solver.o \
	   pnp_solver.o \
	   sim3_solver.o \
	   converter.o \
	   image_converter.o \
	   random_array.o \
	   stereo_rectifier.o \
	   color_scheme.o \
	   viewer.o \

# ------------------------------------------------------------------------------

all : ${OBJS}
	${CC} ${CFLAGS} ${OBJS} ${LIB} ${LIB1} ${LIB2} ${LIB3} ${LIB4} -o ${BIN}

# .cc.o :
	# ${CC} ${CFLAGS} ${INC} ${INCRS} -c $<

# ------------------------------------------------------------------------------

run_camera_slam.o : run_camera_slam.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

system.o : ../src/openvslam/system.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

tracking_module.o : ../src/openvslam/tracking_module.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

mapping_module.o : ../src/openvslam/mapping_module.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

config.o : ../src/openvslam/config.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

global_optimization_module.o : ../src/openvslam/global_optimization_module.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# camera

base.o : ../src/openvslam/camera/base.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

equirectangular.o : ../src/openvslam/camera/equirectangular.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

fisheye.o : ../src/openvslam/camera/fisheye.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

perspective.o : ../src/openvslam/camera/perspective.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# data

bow_database.o : ../src/openvslam/data/bow_database.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

camera_database.o : ../src/openvslam/data/camera_database.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

common.o : ../src/openvslam/data/common.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

frame.o : ../src/openvslam/data/frame.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

frame_statistics.o : ../src/openvslam/data/frame_statistics.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

graph_node.o : ../src/openvslam/data/graph_node.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

keyframe.o : ../src/openvslam/data/keyframe.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

landmark.o : ../src/openvslam/data/landmark.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

map_database.o : ../src/openvslam/data/map_database.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# feature

orb_extractor.o : ../src/openvslam/feature/orb_extractor.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

orb_extractor_node.o : ../src/openvslam/feature/orb_extractor_node.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

orb_params.o : ../src/openvslam/feature/orb_params.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# initialize

init_base.o : ../src/openvslam/initialize/base.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $? -o $@

bearing_vector.o : ../src/openvslam/initialize/bearing_vector.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

init_perspective.o : ../src/openvslam/initialize/perspective.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $? -o $@

# ------------------------------------------------------------------------------
# io

map_database_io.o : ../src/openvslam/io/map_database_io.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

trajectory_io.o : ../src/openvslam/io/trajectory_io.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# match

area.o : ../src/openvslam/match/area.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

bow_tree.o : ../src/openvslam/match/bow_tree.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

fuse.o : ../src/openvslam/match/fuse.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

projection.o : ../src/openvslam/match/projection.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

robust.o : ../src/openvslam/match/robust.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

stereo.o : ../src/openvslam/match/stereo.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# module

frame_tracker.o : ../src/openvslam/module/frame_tracker.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

initializer.o : ../src/openvslam/module/initializer.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

keyframe_inserter.o : ../src/openvslam/module/keyframe_inserter.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

local_map_cleaner.o : ../src/openvslam/module/local_map_cleaner.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

loop_bundle_adjuster.o : ../src/openvslam/module/loop_bundle_adjuster.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

loop_detector.o : ../src/openvslam/module/loop_detector.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

relocalizer.o : ../src/openvslam/module/relocalizer.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

two_view_triangulator.o : ../src/openvslam/module/two_view_triangulator.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# optimize

global_bundle_adjuster.o : ../src/openvslam/optimize/global_bundle_adjuster.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

graph_optimizer.o : ../src/openvslam/optimize/graph_optimizer.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

local_bundle_adjuster.o : ../src/openvslam/optimize/local_bundle_adjuster.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

pose_optimizer.o : ../src/openvslam/optimize/pose_optimizer.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

transform_optimizer.o : ../src/openvslam/optimize/transform_optimizer.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# optimize/g2o

landmark_vertex.o : ../src/openvslam/optimize/g2o/landmark_vertex.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

landmark_vertex_container.o : ../src/openvslam/optimize/g2o/landmark_vertex_container.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# optimize/g2o/se3

equirectangular_pose_opt_edge.o : ../src/openvslam/optimize/g2o/se3/equirectangular_pose_opt_edge.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

equirectangular_reproj_edge.o : ../src/openvslam/optimize/g2o/se3/equirectangular_reproj_edge.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

perspective_pose_opt_edge.o : ../src/openvslam/optimize/g2o/se3/perspective_pose_opt_edge.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

perspective_reproj_edge.o : ../src/openvslam/optimize/g2o/se3/perspective_reproj_edge.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

se3_shot_vertex.o : ../src/openvslam/optimize/g2o/se3/shot_vertex.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $? -o $@

shot_vertex_container.o : ../src/openvslam/optimize/g2o/se3/shot_vertex_container.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# optimize/g2o/sim3

backward_reproj_edge.o : ../src/openvslam/optimize/g2o/sim3/backward_reproj_edge.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

forward_reproj_edge.o : ../src/openvslam/optimize/g2o/sim3/forward_reproj_edge.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

graph_opt_edge.o : ../src/openvslam/optimize/g2o/sim3/graph_opt_edge.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

sim3_shot_vertex.o : ../src/openvslam/optimize/g2o/sim3/shot_vertex.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $? -o $@

transform_vertex.o : ../src/openvslam/optimize/g2o/sim3/transform_vertex.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# publish

frame_publisher.o : ../src/openvslam/publish/frame_publisher.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

map_publisher.o : ../src/openvslam/publish/map_publisher.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# solve

solve_common.o : ../src/openvslam/solve/common.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $? -o $@

essential_solver.o : ../src/openvslam/solve/essential_solver.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

fundamental_solver.o : ../src/openvslam/solve/fundamental_solver.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

homography_solver.o : ../src/openvslam/solve/homography_solver.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

pnp_solver.o : ../src/openvslam/solve/pnp_solver.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

sim3_solver.o : ../src/openvslam/solve/sim3_solver.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# util

converter.o : ../src/openvslam/util/converter.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

image_converter.o : ../src/openvslam/util/image_converter.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

random_array.o : ../src/openvslam/util/random_array.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

stereo_rectifier.o : ../src/openvslam/util/stereo_rectifier.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------
# pangolin_viewer

color_scheme.o : ../src/pangolin_viewer/color_scheme.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

viewer.o : ../src/pangolin_viewer/viewer.cc
	${CC} ${CFLAGS} ${INC} ${INCRS} -c $?

# ------------------------------------------------------------------------------

clean :
	\rm ${BIN} ${OBJS}

長いですが、これはこれで価値があります。短くすることもできます。
仕事で忙しくて人も足りない状況で、このくらい覚える必要があることの数を減らすととりあえず開発に参加してもらって成果を出してもらえます。Makefileとかshとかは本当に独学してくれないものです。
makeは後ほど説明します。

pangolin

pangolinを使います。昔から使ってみたかったからです。


$ git clone https://github.com/stevenlovegrove/Pangolin.git
$ cd Pangolin
$ mkdir build
$ cd build
$ cmake ..
$ make -j2
$ sudo make install

cv-helpers.hpp

cv-helpers.hppで怒られる場合は、下記の記事のシンボリックリンク作成をやってください。

RealSense D455 2

g2o

-DG2O_USE_CSPARSE=ONは必須です。
これをやらないとsolversの下にcsparseが作成されません。

速くなることを期待してMPやらせます。

というかOpenVSLAM Communityからコピーした方がいいと思います。

j2使うとかなり速くなります。
j4はCPUファンが勢いよく回るのでやりません。
j2でも気温によりファンが勢いよく回ります。

NUC11PAHi5


$ cd ~/develop
$ git clone https://github.com/RainerKuemmerle/g2o.git
$ cd g2o
$ mkdir build
$ cd build
$ cmake -DG2O_USE_CSPARSE=ON -DWITH_OPENMP=ON ..
$ make -j2
$ sudo make install

ceres solver


sudo apt install libsuitesparse-dev
sudo apt install libgoogle-glog-dev

$ cd ~/develop
$ git clone https://github.com/ceres-solver/ceres-solver.git
cd ceres-solver
mkdir build
cd build
cmake ..
make -j2
sudo make install

もし、/usr/includeの古いceresを見に行ってしまう場合は/usr/local/includeのsudo make installした方を見に行くように.bashrcを変更しましょう。

変則的な方法として、下記でもいけると思います。
これで上手くいくと-l glogが不要になります。


$ sudo apt install libceres-dev
$ cd ~/develop
$ git clone https://github.com/ceres-solver/ceres-solver.git
$ cd ceres-solver
$ mkdir build
$ cd build
$ cmake ..
$ make -j2
$ sudo make install

残り

openvslam/src/openvslam/io/map_database_io.hに#include <fstream>を追加。
openvslam/src/openvslam/io/trajectory_io.hに#include <fstream>を追加。
openvslam/src/openvslam/publish/frame_publisher.hに#include <iomanip>を追加。

runの準備

実行時、下記のオプションが必須です。
vocab_file_path
cam_num
config_file_path

camera numberはVideoCapture用なので、自分の様に改造した場合は任意の値を入れて大丈夫です。
改造の結果、使わせないようになっています。

下記のようにして実行しますが、準備が必要です。


./SLAM -v ../../orb_vocab.fbow -c euroc/EuRoC_mono.yaml -n 0

orb_vocab.fbow

50MBもあるFBoWでORBでVOCABなものをwgetします。


cd ~/develop
wget https://github.com/OpenVSLAM-Community/FBoW_orb_vocab/raw/main/orb_vocab.fbow

EuRoC_mono.yaml

mono用のyamlを使うわけですが、kittiの方は複数あったので、こちらを使ってみることにしました。

RealSenseとの接続のためにEuRoC_mono.yamlを書き換えます。

Camera.color_order: “Gray”をコメントアウトして”RGB”に変更します。

EuRoC_mono.yaml

# Camera.color_order: "Gray"
Camera.color_order: "RGB"

run


./SLAM -v ../../orb_vocab.fbow -c euroc/EuRoC_mono.yaml -n 0

動画はこちらです。

走らせる 3
走らせる 4

まとめ

OpenVSLAM Communityの方も閉じました。(2022.04.15)
実際に動かすこととKeyframeとかの理解が目的で使っているので自分で実装するのはやぶさかではないけど、復活してもらいたいなあ。
C++/Ruby/JavaScriptの書き方として最も自分に合っている書き方をしてくれているので最高に読みやすい。

こちらになったようです。
stella-cv

広告

IT開発関連書とビジネス書が豊富な翔泳社の通販『SEshop』
さくらのレンタルサーバ
ムームードメイン
Oisix(おいしっくす)
らでぃっしゅぼーや
珈琲きゃろっと
エプソムソルト




«       »