Git Product home page Git Product logo

vins-mono's Introduction

VINS-Mono

A Robust and Versatile Monocular Visual-Inertial State Estimator

11 Jan 2019: An extension of VINS, which supports stereo cameras / stereo cameras + IMU / mono camera + IMU, is published at VINS-Fusion

29 Dec 2017: New features: Add map merge, pose graph reuse, online temporal calibration function, and support rolling shutter camera. Map reuse videos:

cla icra

VINS-Mono is a real-time SLAM framework for Monocular Visual-Inertial Systems. It uses an optimization-based sliding window formulation for providing high-accuracy visual-inertial odometry. It features efficient IMU pre-integration with bias correction, automatic estimator initialization, online extrinsic calibration, failure detection and recovery, loop detection, and global pose graph optimization, map merge, pose graph reuse, online temporal calibration, rolling shutter support. VINS-Mono is primarily designed for state estimation and feedback control of autonomous drones, but it is also capable of providing accurate localization for AR applications. This code runs on Linux, and is fully integrated with ROS. For iOS mobile implementation, please go to VINS-Mobile.

Authors: Tong Qin, Peiliang Li, Zhenfei Yang, and Shaojie Shen from the HKUST Aerial Robotics Group

Videos:

euroc indoor_outdoor AR_demo

EuRoC dataset; Indoor and outdoor performance; AR application;

MAV platform Mobile platform

MAV application; Mobile implementation (Video link for mainland China friends: Video1 Video2 Video3 Video4 Video5)

Related Papers

  • Online Temporal Calibration for Monocular Visual-Inertial Systems, Tong Qin, Shaojie Shen, IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS, 2018), best student paper award pdf

  • VINS-Mono: A Robust and Versatile Monocular Visual-Inertial State Estimator, Tong Qin, Peiliang Li, Zhenfei Yang, Shaojie Shen, IEEE Transactions on Roboticspdf

If you use VINS-Mono for your academic research, please cite at least one of our related papers.bib

1. Prerequisites

1.1 Ubuntu and ROS Ubuntu 16.04. ROS Kinetic. ROS Installation additional ROS pacakge

    sudo apt-get install ros-YOUR_DISTRO-cv-bridge ros-YOUR_DISTRO-tf ros-YOUR_DISTRO-message-filters ros-YOUR_DISTRO-image-transport

1.2. Ceres Solver Follow Ceres Installation, use version 1.14.0 and remember to sudo make install. (There are compilation issues in Ceres versions 2.0.0 and above.)

2. Build VINS-Mono on ROS

Clone the repository and catkin_make:

    cd ~/catkin_ws/src
    git clone https://github.com/HKUST-Aerial-Robotics/VINS-Mono.git
    cd ../
    catkin_make
    source ~/catkin_ws/devel/setup.bash

3. Visual-Inertial Odometry and Pose Graph Reuse on Public datasets

Download EuRoC MAV Dataset. Although it contains stereo cameras, we only use one camera. The system also works with ETH-asl cla dataset. We take EuRoC as the example.

3.1 visual-inertial odometry and loop closure

3.1.1 Open three terminals, launch the vins_estimator , rviz and play the bag file respectively. Take MH_01 for example

    roslaunch vins_estimator euroc.launch 
    roslaunch vins_estimator vins_rviz.launch
    rosbag play YOUR_PATH_TO_DATASET/MH_01_easy.bag 

(If you fail to open vins_rviz.launch, just open an empty rviz, then load the config file: file -> Open Config-> YOUR_VINS_FOLDER/config/vins_rviz_config.rviz)

3.1.2 (Optional) Visualize ground truth. We write a naive benchmark publisher to help you visualize the ground truth. It uses a naive strategy to align VINS with ground truth. Just for visualization. not for quantitative comparison on academic publications.

    roslaunch benchmark_publisher publish.launch  sequence_name:=MH_05_difficult

(Green line is VINS result, red line is ground truth).

3.1.3 (Optional) You can even run EuRoC without extrinsic parameters between camera and IMU. We will calibrate them online. Replace the first command with:

    roslaunch vins_estimator euroc_no_extrinsic_param.launch

No extrinsic parameters in that config file. Waiting a few seconds for initial calibration. Sometimes you cannot feel any difference as the calibration is done quickly.

3.2 map merge

After playing MH_01 bag, you can continue playing MH_02 bag, MH_03 bag ... The system will merge them according to the loop closure.

3.3 map reuse

3.3.1 map save

Set the pose_graph_save_path in the config file (YOUR_VINS_FOLEDER/config/euroc/euroc_config.yaml). After playing MH_01 bag, input s in vins_estimator terminal, then enter. The current pose graph will be saved.

3.3.2 map load

Set the load_previous_pose_graph to 1 before doing 3.1.1. The system will load previous pose graph from pose_graph_save_path. Then you can play MH_02 bag. New sequence will be aligned to the previous pose graph.

4. AR Demo

4.1 Download the bag file, which is collected from HKUST Robotic Institute. For friends in mainland China, download from bag file.

4.2 Open three terminals, launch the ar_demo, rviz and play the bag file respectively.

    roslaunch ar_demo 3dm_bag.launch
    roslaunch ar_demo ar_rviz.launch
    rosbag play YOUR_PATH_TO_DATASET/ar_box.bag 

We put one 0.8m x 0.8m x 0.8m virtual box in front of your view.

5. Run with your device

Suppose you are familiar with ROS and you can get a camera and an IMU with raw metric measurements in ROS topic, you can follow these steps to set up your device. For beginners, we highly recommend you to first try out VINS-Mobile if you have iOS devices since you don't need to set up anything.

5.1 Change to your topic name in the config file. The image should exceed 20Hz and IMU should exceed 100Hz. Both image and IMU should have the accurate time stamp. IMU should contain absolute acceleration values including gravity.

5.2 Camera calibration:

We support the pinhole model and the MEI model. You can calibrate your camera with any tools you like. Just write the parameters in the config file in the right format. If you use rolling shutter camera, please carefully calibrate your camera, making sure the reprojection error is less than 0.5 pixel.

5.3 Camera-Imu extrinsic parameters:

If you have seen the config files for EuRoC and AR demos, you can find that we can estimate and refine them online. If you familiar with transformation, you can figure out the rotation and position by your eyes or via hand measurements. Then write these values into config as the initial guess. Our estimator will refine extrinsic parameters online. If you don't know anything about the camera-IMU transformation, just ignore the extrinsic parameters and set the estimate_extrinsic to 2, and rotate your device set at the beginning for a few seconds. When the system works successfully, we will save the calibration result. you can use these result as initial values for next time. An example of how to set the extrinsic parameters is inextrinsic_parameter_example

5.4 Temporal calibration: Most self-made visual-inertial sensor sets are unsynchronized. You can set estimate_td to 1 to online estimate the time offset between your camera and IMU.

5.5 Rolling shutter: For rolling shutter camera (carefully calibrated, reprojection error under 0.5 pixel), set rolling_shutter to 1. Also, you should set rolling shutter readout time rolling_shutter_tr, which is from sensor datasheet(usually 0-0.05s, not exposure time). Don't try web camera, the web camera is so awful.

5.6 Other parameter settings: Details are included in the config file.

5.7 Performance on different devices:

(global shutter camera + synchronized high-end IMU, e.g. VI-Sensor) > (global shutter camera + synchronized low-end IMU) > (global camera + unsync high frequency IMU) > (global camera + unsync low frequency IMU) > (rolling camera + unsync low frequency IMU).

6. Docker Support

To further facilitate the building process, we add docker in our code. Docker environment is like a sandbox, thus makes our code environment-independent. To run with docker, first make sure ros and docker are installed on your machine. Then add your account to docker group by sudo usermod -aG docker $YOUR_USER_NAME. Relaunch the terminal or logout and re-login if you get Permission denied error, type:

cd ~/catkin_ws/src/VINS-Mono/docker
make build
./run.sh LAUNCH_FILE_NAME   # ./run.sh euroc.launch

Note that the docker building process may take a while depends on your network and machine. After VINS-Mono successfully started, open another terminal and play your bag file, then you should be able to see the result. If you need modify the code, simply run ./run.sh LAUNCH_FILE_NAME after your changes.

7. Acknowledgements

We use ceres solver for non-linear optimization and DBoW2 for loop detection, and a generic camera model.

8. Licence

The source code is released under GPLv3 license.

We are still working on improving the code reliability. For any technical issues, please contact Tong QIN <tong.qinATconnect.ust.hk> or Peiliang LI <pliapATconnect.ust.hk>.

For commercial inquiries, please contact Shaojie SHEN <eeshaojieATust.hk>

vins-mono's People

Contributors

chobitsfan avatar huahang avatar peiliangli avatar qintonguav avatar shaojie avatar shaozu avatar xuhao1 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

vins-mono's Issues

A special case which can cause diverge

imu
The above picture is the imu read from pixhawk. Everything goes well before imu data surge to(35m^s-2) ,(This happens when my quadrotor hit something) ,then the odometry diverge,(in about 3 seconds, it would goes 20 meters), Which i think may need to take care of this case ,the imu read is not normal.In quadrotor it must be crash.
But why when the quadrotor hit something(imu surge just 1 second) , then it landdown(imu read normal), the odometry still drift.
true

navigation

how can i replay the navigation with voxel map like in video4 ? very kind of you for any reference.

cannot launch feature_tracker

Hi, thank you for your valuable open-source code.

By the way, I cannot launch the feature_tracker packge.

I'm trying to run in the Nvidia TX1, ubuntu 16.04, ROS Kinetic.

When I launch >> roslaunch vins_estimator euroc.launch

ubuntu@tegra-ubuntu:~/catkin_ws$ roslaunch vins_estimator euroc.launch
... logging to /home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/roslaunch-tegra-ubuntu-10137.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://tegra-ubuntu:39893/

SUMMARY

PARAMETERS

  • /feature_tracker/config_file: /home/ubuntu/catk...
  • /feature_tracker/vins_folder: /home/ubuntu/catk...
  • /rosdistro: kinetic
  • /rosversion: 1.12.7
  • /vins_estimator/config_file: /home/ubuntu/catk...
  • /vins_estimator/vins_folder: /home/ubuntu/catk...

NODES
/
feature_tracker (feature_tracker/feature_tracker)
vins_estimator (vins_estimator/vins_estimator)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[feature_tracker-1]: started with pid [10155]
process[vins_estimator-2]: started with pid [10156]
OpenCV Error: Bad argument (Invalid pointer to file storage) in cvGetFileNodeByName, file /tmp/binarydeb/ros-kinetic-opencv3-3.2.0/modules/core/src/persistence.cpp, line 863
terminate called after throwing an instance of 'cv::Exception'
what(): /tmp/binarydeb/ros-kinetic-opencv3-3.2.0/modules/core/src/persistence.cpp:863: error: (-5) Invalid pointer to file storage in function cvGetFileNodeByName

[ INFO] [1497969209.836649578]: init begins

[feature_tracker-1] process has died [pid 10155, exit code -6, cmd /home/ubuntu/catkin_ws/devel/lib/feature_tracker/feature_tracker __name:=feature_tracker __log:=/home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/feature_tracker-1.log].

log file: /home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/feature_tracker-1*.log

[ INFO] [1497969209.853653828]: Loaded config_file: /home/ubuntu/catkin_ws/src/VINS-Mono/feature_tracker/../config/euroc/euroc_config.yaml
[ INFO] [1497969209.855908798]: Loaded vins_folder: /home/ubuntu/catkin_ws/src/VINS-Mono/feature_tracker/../config/../
[ WARN] [1497969209.856349729]: Optimize extrinsic param around initial guess!
[ INFO] [1497969209.857591900]: Extrinsic_R :
2.22045e-16 -1 0
1 2.22045e-16 0
0 0 1
[ INFO] [1497969209.857880906]: Extrinsic_T :
-0.02 -0.06 0.01
[ WARN] [1497969209.858156528]: waiting for image and imu...
[ WARN] [1497969209.917905097]: DATA SUBSCRIBED
[ WARN] [1497969209.918072907]: LOOP_CLOSURE true
voc file: /home/ubuntu/catkin_ws/src/VINS-Mono/feature_tracker/../config/..//support_files/brief_k10L6.bin
OpenCV Error: Bad argument (Invalid pointer to file storage) in cvGetFileNodeByName, file /tmp/binarydeb/ros-kinetic-opencv3-3.2.0/modules/core/src/persistence.cpp, line 863
terminate called after throwing an instance of 'cv::Exception'
what(): /tmp/binarydeb/ros-kinetic-opencv3-3.2.0/modules/core/src/persistence.cpp:863: error: (-5) Invalid pointer to file storage in function cvGetFileNodeByName
[vins_estimator-2] process has died [pid 10156, exit code -6, cmd /home/ubuntu/catkin_ws/devel/lib/vins_estimator/vins_estimator __name:=vins_estimator __log:=/home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/vins_estimator-2.log].
log file: /home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/vins_estimator-2
.log
all processes on machine have died, roslaunch will exit
*
shutting down processing monitor...
... shutting down processing monitor complete

done

Therefore I try to launch feature_tracker directly to see the error part, it shows


ubuntu@tegra-ubuntu:~/catkin_ws$ roslaunch feature_tracker euroc.launch
... logging to /home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/roslaunch-tegra-ubuntu-9993.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://tegra-ubuntu:45356/

SUMMARY

PARAMETERS

  • /feature_tracker/F_threshold: 1.0
  • /feature_tracker/calib_dir: /home/ubuntu/catk...
  • /feature_tracker/cam_name0: euroc0_camera_cal...
  • /feature_tracker/equalize: False
  • /feature_tracker/fisheye: False
  • /feature_tracker/freq: 1
  • /feature_tracker/max_cnt: 200
  • /feature_tracker/min_dist: 20
  • /feature_tracker/show_track: True
  • /rosdistro: kinetic
  • /rosversion: 1.12.7

NODES
/
feature_tracker (feature_tracker/feature_tracker)
player (rosbag/play)

auto-starting new master
process[master]: started with pid [10004]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 00587f2e-55c5-11e7-a1fc-00044b57fe0c
process[rosout-1]: started with pid [10017]
started core service [/rosout]
process[player-2]: started with pid [10024]
process[feature_tracker-3]: started with pid [10033]
[ERROR] [1497969027.609730521]: Failed to load config_file
OpenCV Error: Null pointer (NULL or empty buffer) in cvOpenFileStorage, file /tmp/binarydeb/ros-kinetic-opencv3-3.2.0/modules/core/src/persistence.cpp, line 4153
terminate called after throwing an instance of 'cv::Exception'
what(): /tmp/binarydeb/ros-kinetic-opencv3-3.2.0/modules/core/src/persistence.cpp:4153: error: (-27) NULL or empty buffer in function cvOpenFileStorage

[feature_tracker-3] process has died [pid 10033, exit code -6, cmd /home/ubuntu/catkin_ws/devel/lib/feature_tracker/feature_tracker ~imu:=/imu0 ~raw_image:=/cam0/image_raw __name:=feature_tracker __log:=/home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/feature_tracker-3.log].
log file: /home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/feature_tracker-3*.log
[player-2] process has finished cleanly
log file: /home/ubuntu/.ros/log/00587f2e-55c5-11e7-a1fc-00044b57fe0c/player-2*.log

Actually I still not understood the meaning of below two list, in the feature_tracker/launch/euroc.launch
param name="calib_dir" type="string" value="$(find feature_tracker)/config/" />
param name="cam_name0" type="string" value="euroc0_camera_calib_mei.yaml" />

Thanks.

In double2vector(), why do you only use yaw_diff to update states?

From my understanding, in Estimator::optimization(), you update states(Rs, Ps, Vs, Bas, Bgs) after a round of optimization using Estimator::double2vector(). And there in double2vector(), you update states Ps, Vs and Rs in sliding window with a rot_diff matrix. What confuses me is the way rot_diff computed, because you just set pitch and roll to zero to pass to Utility::ypr2R().
117681

Could I know the reason for such an operation? Looking forward to your answer.

Question about mid-point integration in integration_base.h

In your paper TRO VINS-Mono: A Robust and Versatile Monocular Visual-Inertial State Estimator, you've demonstrated the Euler integration procedure in an understandable and elegant manner. At the same time, your implementation chooses Mid-point integration, as is shown in VINS-Mono project.
In method IntegrationBase::midPointIntegration(), I see that you propagate jacobian and covariance with similar formular as (10) and (11) in TRO,
1766
17661
I mean,
1766661

What I do not understand is that how F and V are computed?
176665253

Are there corresponding formulas in your other papers? I'd appreciate it if you can provide any information about this. Thank much again for your outstanding work.

How to set the initial parameters of imu?

Hello,
In your configuration folder /config/euroc_config.yaml, here we need to configure the parameters of imu, including accelerometer measurement noise standard deviation acc_n, gyroscope measurement noise standard deviation gyr_n and gyroscope bias random work noise standard gyr_w.

But when using our own hardware(camera+imu), how to get the IMU parameters?

Here, you said, "The more accurate parameters you provide, the better performance." But I guess that these parameters will be changed via nonlinear optimization equation, and that means they are not that important just as the initial value of the optimization. I do not know if the understanding is correct.
Thank you.

1

ROS dependency

Hi , thank you for this open source work
i want to run VINS-MONO on LINUX without ROS , is that possible ?
if its possible , any suggestion about how to remove ROS dependency ?
regards ;

Question about tracking failure

Hi !
I used my camera and IMU to test the AR_Demo and found that this problem occurs when the rotation is faster or the screen is suddenly blocked.
2017-06-26 11 55 24
Is it due to the fact that the two images can not match enough feature points when solving the PnP ?
2017-06-26 15 19 59
Is there any re initialization function after the trace failed? Or can I move the camera and reposition to a previous frame when tracking failure?
Thank you!

test on intel euclid

Hi!
We are testing the vins-mono on the intel euclid, of which the cpu is Intel® Atom™ x7-8700 Quad-Core.

When we run the sample launch file: roslaunch vins_estimator euroc.launch, we found the odometry
only updated at 5Hz.

Then we also tried the vins-estimator with the onboard imu and pinhole camera, but we could not get the convergent result(of course we modified the yaml file for the basic parameter).

Any suggestion about the low frequency and bad vins result?

some doubt about code and paper

I have several question about the code and paper.

  1. the formula
    screenshot from 2017-07-03 22 39 53
    why it just minus the noise bias without the noise. The true acceleration should be
    $$a_t = a_m + b_{at} + n_{at}$$, or we can think the noise is gauss distribution ,the mean value is 0.

screenshot from 2017-07-03 22 48 14

    Eigen::Vector3d b1, b2;
    Eigen::Vector3d a = pts_j.normalized();
    Eigen::Vector3d tmp(0, 0, 1);
    if(a == tmp)
        tmp << 1, 0, 0;
    b1 = (tmp - a * (a.transpose() * tmp)).normalized();
    b2 = a.cross(b1);
    tangent_base.block<1, 3>(0, 0) = b1.transpose();
    tangent_base.block<1, 3>(1, 0) = b2.transpose();

I understand the algorithmn you describe in your paper ,use two cross product to construct it. But I donot
know the math in your code , even i know i test it is right.

void Estimator::slideWindow()
{
    TicToc t_margin;
    if (marginalization_flag == MARGIN_OLD)
    {
        back_R0 = Rs[0];
        back_P0 = Ps[0];
        if (frame_count == WINDOW_SIZE)
        {
            for (int i = 0; i < WINDOW_SIZE; i++)
            {
                Rs[i].swap(Rs[i + 1]);

                std::swap(pre_integrations[i], pre_integrations[i + 1]);

                dt_buf[i].swap(dt_buf[i + 1]);
                linear_acceleration_buf[i].swap(linear_acceleration_buf[i + 1]);
                angular_velocity_buf[i].swap(angular_velocity_buf[i + 1]);

                Headers[i] = Headers[i + 1];
                Ps[i].swap(Ps[i + 1]);
                Vs[i].swap(Vs[i + 1]);
            }
     }
}

Why donot exchange imu bias noise , add these code

 Bas[i].swap(Bas[i+1]);
 Bgs[i].swap(Bgs[i +1]);

Thank you for your great job.

Question about timing statistics of your VINS framework

Qin,
My github corrupts, so I have to contact you by email. I notice in paper Monocular Visual-Inertial State Estimation for Mobile Augmented Reality(ISMAR) that on an iPhone device, the VINS runs with below timing statistics(Table 1):
121

Herein, Loop detection in thread 3 costs 60 ms.

On the other hand, in your another paper, i.e. VINS-Mono: A robust and Versatile Monocular Visual-Inertial State Estimator(TRO), I see that on an Inter i7 platform, the timing statistics behaves as below:
122
Here, in thread 3, the loop detection time becomes 100 ms. I cannot understand why a cellphone diveice has a better performance in timing than a powerful PC?

Look forward to your answer.

Running on odroid XU4

It is really exciting to see this code released! Amazing!
I am working with Odroid XU4.
I am wondering if it is possible to run it in ARM CPUs directly?
or any changes to be made for that?

Kind Regards,
Chang

code problem

In the function FeatureTracker::readImage(const cv::Mat &_img),the variable img_cnt doesn't make any change all the time.So the prev_img is equals to curr_img.I wonder if this is a bug.

Can't find the code about advertising topic "/feature_tracker/feature"

Hi,I'm a newbie at ROS . When performance on EuRoC dataset ,I use rqt_graph get the communication between nodes as follows:
topic
Does it mean node "feature_tracker" advertise topic "/feature_tracker/feature" ,and node "vins_estimator" subscribe topic "/feature_tracker/feature"? I can find the code "n.subscribe("/feature_tracker/feature", 2000, feature_callback)" in estimator_node.cpp, but can't find relative code in feature_tracker_node.cpp.
So I wonder in where the topic "/feature_tracker/feature" been advertised.

Question about the code

I read some code without debugging because of none ROS developing experience, and have some question:

  1. It seems that the program can be divided into 2 parts: feature_tracker and vins_estimator and if I compile the whole program, I can get 2 executable file. In my view, vins_estimator is used for the whole estimating procedure, and the features of image are supplied by feature_tracker, is it right?
  2. The estimator_node is the 'start point' of vins_estimator, and it will start the thread 'process' which is used to collect imu and image data and process them, at the same time the program can receive and store imu and image data from ROS , is it right?
  3. loop closure initialization procedure is carried out in 'process'. if the second latest frame is keyframe, then marginalize the oldest frame, if not, then marginalize the frame. But I don't know the meaning of variable 'keyframe_freq' and why the keyframe should be added every 3 times in the loop?

4.Will VINS have none ROS version or already have like ORB-SLAM, so more developer can modify it more easily?

Question about result

I have successful run in my PC but I have some questions about the result
What is the meaning of each of the vins_result.csv in the config file after running the code?
Is the real coordinates of the camera output on the command line?

image

Camera position is randomly drifting away

Hi, thanks for sharing the implementation. There were some issues when I testing with my own data (collected from an android mobile phone).

screenshot from 2017-06-28 10-53-26

As shown in the screenshot, the camera randomly drifting away, usually after a camera movement but could also happen when it's almost static.

The camera path seems very inaccurate as well, though it works fine with only camera rotation.

Since the timestamp might be inaccurate or unsynchronised, I tried few ways to fix that but still unlucky. So I'm wondering if there might be any other possible reasons for causing this?


The iOS version works really nice, so I'll further test it with the data collected from iphone and report the result.

catkin_make error

ubuntu 16.04 kinetic
when i use catkin_make, i encountored error as follows:
[ 0%] Built target nav_msgs_generate_messages_nodejs
[ 0%] Built target std_msgs_generate_messages_nodejs
[ 0%] Built target _hector_nav_msgs_generate_messages_check_deps_GetSearchPosition
[ 0%] Built target _hector_nav_msgs_generate_messages_check_deps_GetDistanceToObstacle
[ 0%] Built target _hector_nav_msgs_generate_messages_check_deps_GetRecoveryInfo
[ 0%] Built target _hector_nav_msgs_generate_messages_check_deps_GetRobotTrajectory
[ 0%] Built target nav_msgs_generate_messages_lisp
[ 0%] Built target std_msgs_generate_messages_lisp
[ 0%] Built target nav_msgs_generate_messages_eus
[ 0%] Built target std_msgs_generate_messages_py
[ 0%] Built target nav_msgs_generate_messages_py
[ 0%] Built target std_msgs_generate_messages_eus
[ 0%] Built target _hector_nav_msgs_generate_messages_check_deps_GetNormal
Scanning dependencies of target benchmark_publisher
Scanning dependencies of target camera_model
[ 0%] Built target std_msgs_generate_messages_cpp
[ 0%] Built target nav_msgs_generate_messages_cpp
Scanning dependencies of target roscpp_generate_messages_py
[ 0%] Built target roscpp_generate_messages_py
[ 0%] Built target _catkin_empty_exported_target
[ 0%] Built target geometry_msgs_generate_messages_py
[ 0%] Built target actionlib_msgs_generate_messages_nodejs
[ 0%] Built target geometry_msgs_generate_messages_nodejs
[ 0%] Built target geometry_msgs_generate_messages_cpp
[ 0%] Built target geometry_msgs_generate_messages_eus
[ 0%] Built target actionlib_msgs_generate_messages_eus
[ 0%] Built target actionlib_msgs_generate_messages_py
[ 0%] Built target geometry_msgs_generate_messages_lisp
[ 0%] Built target actionlib_msgs_generate_messages_lisp
[ 0%] Built target actionlib_msgs_generate_messages_cpp
Scanning dependencies of target rosgraph_msgs_generate_messages_eus
Scanning dependencies of target rosgraph_msgs_generate_messages_cpp
[ 0%] Built target rosgraph_msgs_generate_messages_eus
[ 0%] Built target rosgraph_msgs_generate_messages_cpp
Scanning dependencies of target rosgraph_msgs_generate_messages_nodejs
Scanning dependencies of target roscpp_generate_messages_cpp
[ 0%] Built target rosgraph_msgs_generate_messages_nodejs
[ 0%] Built target roscpp_generate_messages_cpp
Scanning dependencies of target roscpp_generate_messages_lisp
Scanning dependencies of target roscpp_generate_messages_eus
[ 0%] Built target roscpp_generate_messages_eus
[ 0%] Built target roscpp_generate_messages_lisp
Scanning dependencies of target rosgraph_msgs_generate_messages_lisp
Scanning dependencies of target rosgraph_msgs_generate_messages_py
[ 0%] Built target rosgraph_msgs_generate_messages_lisp
[ 0%] Built target rosgraph_msgs_generate_messages_py
Scanning dependencies of target roscpp_generate_messages_nodejs
[ 0%] Built target roscpp_generate_messages_nodejs
[ 5%] Built target rplidarNode
[ 6%] Built target rplidarNodeClient
[ 7%] Built target imu_attitude_to_tf_node
[ 9%] Built target map_to_image_node
[ 9%] Built target visualization_msgs_generate_messages_cpp
Scanning dependencies of target tf2_msgs_generate_messages_py
[ 9%] Built target tf2_msgs_generate_messages_py
Scanning dependencies of target tf2_msgs_generate_messages_eus
[ 9%] Built target tf2_msgs_generate_messages_eus
Scanning dependencies of target actionlib_generate_messages_py
[ 9%] Built target actionlib_generate_messages_py
Scanning dependencies of target actionlib_generate_messages_nodejs
[ 9%] Built target actionlib_generate_messages_nodejs
Scanning dependencies of target actionlib_generate_messages_lisp
[ 9%] Built target actionlib_generate_messages_lisp
Scanning dependencies of target actionlib_generate_messages_cpp
[ 9%] Built target actionlib_generate_messages_cpp
[ 11%] Built target pose_and_orientation_to_imu_node
Scanning dependencies of target sensor_msgs_generate_messages_py
Scanning dependencies of target tf2_msgs_generate_messages_cpp
[ 11%] Built target tf2_msgs_generate_messages_cpp
[ 11%] Built target sensor_msgs_generate_messages_py
Scanning dependencies of target sensor_msgs_generate_messages_nodejs
Scanning dependencies of target tf_generate_messages_nodejs
[ 11%] Built target sensor_msgs_generate_messages_nodejs
[ 11%] Built target tf_generate_messages_nodejs
Scanning dependencies of target tf_generate_messages_eus
Scanning dependencies of target sensor_msgs_generate_messages_cpp
[ 11%] Built target tf_generate_messages_eus
[ 11%] Built target sensor_msgs_generate_messages_cpp
Scanning dependencies of target tf2_msgs_generate_messages_nodejs
Scanning dependencies of target tf_generate_messages_lisp
[ 11%] Built target tf2_msgs_generate_messages_nodejs
[ 11%] Built target tf_generate_messages_lisp
Scanning dependencies of target tf_generate_messages_py
Scanning dependencies of target sensor_msgs_generate_messages_eus
[ 11%] Built target tf_generate_messages_py
[ 11%] Built target sensor_msgs_generate_messages_eus
Scanning dependencies of target tf_generate_messages_cpp
Scanning dependencies of target actionlib_generate_messages_eus
[ 11%] Built target tf_generate_messages_cpp
[ 11%] Built target actionlib_generate_messages_eus
Scanning dependencies of target sensor_msgs_generate_messages_lisp
Scanning dependencies of target tf2_msgs_generate_messages_lisp
[ 11%] Built target tf2_msgs_generate_messages_lisp
[ 11%] Built target sensor_msgs_generate_messages_lisp
[ 11%] Built target visualization_msgs_generate_messages_nodejs
[ 11%] Built target visualization_msgs_generate_messages_eus
[ 11%] Built target visualization_msgs_generate_messages_lisp
[ 11%] Built target visualization_msgs_generate_messages_py
[ 11%] Built target _hector_mapping_generate_messages_check_deps_HectorDebugInfo
[ 15%] Built target hector_nav_msgs_generate_messages_nodejs
[ 15%] Built target _hector_mapping_generate_messages_check_deps_HectorIterData
[ 19%] Built target hector_nav_msgs_generate_messages_lisp
[ 24%] Built target hector_nav_msgs_generate_messages_eus
[ 32%] Built target hector_nav_msgs_generate_messages_cpp
[ 34%] Built target hector_nav_msgs_generate_messages_py
[ 35%] Built target hector_mapping_generate_messages_cpp
[ 36%] Built target hector_mapping_generate_messages_nodejs
[ 41%] Built target hector_mapping_generate_messages_lisp
[ 41%] Built target hector_mapping_generate_messages_py
[ 41%] Built target hector_nav_msgs_generate_messages
[ 44%] Built target hector_mapping_generate_messages_eus
[ 45%] Built target hector_map_server
[ 47%] Built target geotiff_writer
[ 49%] Built target hector_trajectory_server
[ 53%] Built target hector_mapping
[ 53%] Built target hector_mapping_generate_messages
[ 54%] Built target geotiff_saver
[ 56%] Built target geotiff_node
[ 58%] Built target hector_geotiff_plugins
[ 59%] Building CXX object VINS-Mono/benchmark_publisher/CMakeFiles/benchmark_publisher.dir/src/benchmark_publisher_node.cpp.o
[ 60%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/chessboard/Chessboard.cc.o
[ 61%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/Camera.cc.o
[ 61%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/calib/CameraCalibration.cc.o
[ 62%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CameraFactory.cc.o
[ 63%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CostFunctionFactory.cc.o
[ 65%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CataCamera.cc.o
[ 65%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/PinholeCamera.cc.o
/home/cc/catkin_ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp: In function ‘int main(int, char**)’:
/home/cc/catkin_ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp:143:25: warning: ignoring return value of ‘char* fgets(char*, int, FILE*)’, declared with attribute warn_unused_result [-Wunused-result]
fgets(tmp, 10000, f);
^
/home/cc/catkin_ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp: In constructor ‘Data::Data(FILE*)’:
/home/cc/catkin_ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp:44:30: warning: ignoring return value of ‘int fscanf(FILE*, const char*, ...)’, declared with attribute warn_unused_result [-Wunused-result]
&ax, &ay, &az);
^
[ 65%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/EquidistantCamera.cc.o
[ 67%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/ScaramuzzaCamera.cc.o
[ 68%] Linking CXX executable /home/cc/catkin_ws/devel/lib/benchmark_publisher/benchmark_publisher
[ 68%] Built target benchmark_publisher
[ 69%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/sparse_graph/Transform.cc.o
[ 70%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/gpl/gpl.cc.o
[ 71%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/gpl/EigenQuaternionParameterization.cc.o
[ 72%] Linking CXX static library /home/cc/catkin_ws/devel/lib/libcamera_model.a
[ 72%] Built target camera_model
Scanning dependencies of target vins_estimator
Scanning dependencies of target ar_demo_node
Scanning dependencies of target feature_tracker
[ 72%] Building CXX object VINS-Mono/ar_demo/CMakeFiles/ar_demo_node.dir/src/ar_demo_node.cpp.o
[ 73%] Building CXX object VINS-Mono/feature_tracker/CMakeFiles/feature_tracker.dir/src/feature_tracker_node.cpp.o
[ 73%] Building CXX object VINS-Mono/feature_tracker/CMakeFiles/feature_tracker.dir/src/parameters.cpp.o
[ 74%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator_node.cpp.o
/home/cc/catkin_ws/src/VINS-Mono/vins_estimator/src/estimator_node.cpp:18:38: fatal error: diagnostic_msgs/KeyValue.h: No such file or directory
compilation terminated.
VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/build.make:62: recipe for target 'VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator_node.cpp.o' failed
make[2]: *** [VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator_node.cpp.o] Error 1
CMakeFiles/Makefile2:4361: recipe for target 'VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/all' failed
make[1]: *** [VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
[ 75%] Building CXX object VINS-Mono/feature_tracker/CMakeFiles/feature_tracker.dir/src/feature_tracker.cpp.o
[ 76%] Linking CXX executable /home/cc/catkin_ws/devel/lib/feature_tracker/feature_tracker
[ 77%] Linking CXX executable /home/cc/catkin_ws/devel/lib/ar_demo/ar_demo_node
[ 77%] Built target ar_demo_node
[ 77%] Built target feature_tracker
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed
cc@cc-K55VD:~/catkin_ws$

The problem of MH_05_difficult result

This is my running result of MH_05_difficult dateset,maybe there is something wrong.I did not make any changes to your code. Could you please help me do an analysis ?Thanks!
qq 20170609144449

confi file issues

Hi ,
thank you for this work
im using Loitor_VI_Sensor_SDK_V1.3.1 to run the VINS , imu topic is /imu0 , camera topic is cam0/image_raw/ . what should i modify in the conf file ? no image in the tracked image ,
ros topic list
/benchmark_publisher/path
/cam0/image_raw
/cam0/image_raw/compressed
/cam0/image_raw/compressed/parameter_descriptions
/cam0/image_raw/compressed/parameter_updates
/cam0/image_raw/compressedDepth
/cam0/image_raw/compressedDepth/parameter_descriptions
/cam0/image_raw/compressedDepth/parameter_updates
/cam0/image_raw/theora
/cam0/image_raw/theora/parameter_descriptions
/cam0/image_raw/theora/parameter_updates
/cam1/image_raw
/cam1/image_raw/compressed
/cam1/image_raw/compressed/parameter_descriptions
/cam1/image_raw/compressed/parameter_updates
/cam1/image_raw/compressedDepth
/cam1/image_raw/compressedDepth/parameter_descriptions
/cam1/image_raw/compressedDepth/parameter_updates
/cam1/image_raw/theora
/cam1/image_raw/theora/parameter_descriptions
/cam1/image_raw/theora/parameter_updates
/clicked_point
/feature_tracker/feature_img
/imu0
/initialpose
/move_base_simple/goal
/rosout
/rosout_agg
/tf
/tf_static
/vins_estimator/camera_pose_visual
/vins_estimator/history_cloud
/vins_estimator/path
/vins_estimator/point_cloud
/vins_estimator/pose_graph

also i tried to launch vins_estimator euroc.launch i got this errors
amrani@amrani-200:~$ roslaunch vins_estimator euroc.launch
... logging to /home/amrani/.ros/log/8ee5db0c-5321-11e7-b171-88d7f640a563/roslaunch-amrani-200-28097.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://amrani-200:44949/

SUMMARY

PARAMETERS

  • /feature_tracker/config_file: /home/amrani/catk...
  • /feature_tracker/vins_folder: /home/amrani/catk...
  • /rosdistro: indigo
  • /rosversion: 1.11.21
  • /vins_estimator/config_file: /home/amrani/catk...
  • /vins_estimator/vins_folder: /home/amrani/catk...

NODES
/
feature_tracker (feature_tracker/feature_tracker)
vins_estimator (vins_estimator/vins_estimator)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[feature_tracker-1]: started with pid [28115]
process[vins_estimator-2]: started with pid [28116]
[ INFO] [1497683371.912828312]: init begins
[ INFO] [1497683371.917268213]: Loaded config_file: /home/amrani/catkin_ws/src/VINS-Mono/feature_tracker/../config/euroc/euroc_config.yaml
ERROR: Wrong path to settings
[ INFO] [1497683371.917732996]: Loaded vins_folder: /home/amrani/catkin_ws/src/VINS-Mono/feature_tracker/../config/../
OpenCV Error: Bad argument (Invalid pointer to file storage) in cvGetFileNodeByName, file /build/buildd/opencv-2.4.8+dfsg1/modules/core/src/persistence.cpp, line 740
terminate called after throwing an instance of 'cv::Exception'
what(): /build/buildd/opencv-2.4.8+dfsg1/modules/core/src/persistence.cpp:740: error: (-5) Invalid pointer to file storage in function cvGetFileNodeByName

OpenCV Error: Bad argument (Invalid pointer to file storage) in cvGetFileNodeByName, file /build/buildd/opencv-2.4.8+dfsg1/modules/core/src/persistence.cpp, line 740
terminate called after throwing an instance of 'cv::Exception'
what(): /build/buildd/opencv-2.4.8+dfsg1/modules/core/src/persistence.cpp:740: error: (-5) Invalid pointer to file storage in function cvGetFileNodeByName

[feature_tracker-1] process has died [pid 28115, exit code -6, cmd /home/amrani/catkin_ws/devel/lib/feature_tracker/feature_tracker __name:=feature_tracker __log:=/home/amrani/.ros/log/8ee5db0c-5321-11e7-b171-88d7f640a563/feature_tracker-1.log].
log file: /home/amrani/.ros/log/8ee5db0c-5321-11e7-b171-88d7f640a563/feature_tracker-1*.log
[vins_estimator-2] process has died [pid 28116, exit code -6, cmd /home/amrani/catkin_ws/devel/lib/vins_estimator/vins_estimator __name:=vins_estimator __log:=/home/amrani/.ros/log/8ee5db0c-5321-11e7-b171-88d7f640a563/vins_estimator-2.log].
log file: /home/amrani/.ros/log/8ee5db0c-5321-11e7-b171-88d7f640a563/vins_estimator-2*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done
amrani@amrani-200:~$

Regrads

catkin_make failed

@qintony Hi,I've already install ceres and other dependencies,however I cannot catkin_make sucessfully. How can I solve these problems? Thank you.

Base path: /home/ubuntu/vins-ws
Source space: /home/ubuntu/vins-ws/src
Build space: /home/ubuntu/vins-ws/build
Devel space: /home/ubuntu/vins-ws/devel
Install space: /home/ubuntu/vins-ws/install

Running command: "cmake /home/ubuntu/vins-ws/src -DCATKIN_DEVEL_PREFIX=/home/ubuntu/vins-ws/devel -DCMAKE_INSTALL_PREFIX=/home/ubuntu/vins-ws/install -G Unix Makefiles" in "/home/ubuntu/vins-ws/build"

-- Using CATKIN_DEVEL_PREFIX: /home/ubuntu/vins-ws/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/kinetic
-- This workspace overlays: /opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/ubuntu/vins-ws/build/test_results
-- Found gtest sources under '/usr/src/gtest': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.6
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~ traversing 5 packages in topological order:
-- ~~ - benchmark_publisher
-- ~~ - camera_model
-- ~~ - ar_demo
-- ~~ - feature_tracker
-- ~~ - vins_estimator
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'benchmark_publisher'
-- ==> add_subdirectory(VINS-Mono/benchmark_publisher)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- +++ processing catkin package: 'camera_model'
-- ==> add_subdirectory(VINS-Mono/camera_model)
-- Boost version: 1.58.0
-- Found the following Boost libraries:
-- filesystem
-- program_options
-- system
-- Found OpenCV: /opt/ros/kinetic (found version "3.2.0")
-- Found required Ceres dependency: Eigen version 3.2.92 in /usr/include/eigen3
-- Found required Ceres dependency: glog
-- Performing Test GFLAGS_IN_GOOGLE_NAMESPACE
-- Performing Test GFLAGS_IN_GOOGLE_NAMESPACE - Success
-- Found required Ceres dependency: gflags
-- Found Ceres version: 1.12.0 installed in: /usr/local with components: [LAPACK, SuiteSparse, SparseLinearAlgebraLibrary, SchurSpecializations, OpenMP]
CMake Warning at /opt/ros/kinetic/share/catkin/cmake/catkin_package.cmake:166 (message):
catkin_package() DEPENDS on 'system_lib' but neither
'system_lib_INCLUDE_DIRS' nor 'system_lib_LIBRARIES' is defined.
Call Stack (most recent call first):
/opt/ros/kinetic/share/catkin/cmake/catkin_package.cmake:102 (_catkin_package)
VINS-Mono/camera_model/CMakeLists.txt:23 (catkin_package)

-- +++ processing catkin package: 'ar_demo'
-- ==> add_subdirectory(VINS-Mono/ar_demo)
-- +++ processing catkin package: 'feature_tracker'
-- ==> add_subdirectory(VINS-Mono/feature_tracker)
-- +++ processing catkin package: 'vins_estimator'
-- ==> add_subdirectory(VINS-Mono/vins_estimator)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Found required Ceres dependency: Eigen version 3.2.92 in /usr/include/eigen3
-- Found required Ceres dependency: glog
-- Found required Ceres dependency: gflags
-- Found Ceres version: 1.12.0 installed in: /usr/local with components: [LAPACK, SuiteSparse, SparseLinearAlgebraLibrary, SchurSpecializations, OpenMP]
-- Configuring done
-- Generating done
-- Build files have been written to: /home/ubuntu/vins-ws/build

Running command: "make -j4 -l4" in "/home/ubuntu/vins-ws/build"

Scanning dependencies of target benchmark_publisher
Scanning dependencies of target camera_model
[ 2%] Building CXX object VINS-Mono/benchmark_publisher/CMakeFiles/benchmark_publisher.dir/src/benchmark_publisher_node.cpp.o
[ 4%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/chessboard/Chessboard.cc.o
[ 8%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/calib/CameraCalibration.cc.o
[ 8%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/Camera.cc.o
[ 10%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CameraFactory.cc.o
/home/ubuntu/vins-ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp: In function ‘int main(int, char**)’:
/home/ubuntu/vins-ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp:141:25: warning: ignoring return value of ‘char* fgets(char*, int, FILE*)’, declared with attribute warn_unused_result [-Wunused-result]
fgets(tmp, 10000, f);
^
/home/ubuntu/vins-ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp: In constructor ‘Data::Data(FILE*)’:
/home/ubuntu/vins-ws/src/VINS-Mono/benchmark_publisher/src/benchmark_publisher_node.cpp:42:30: warning: ignoring return value of ‘int fscanf(FILE*, const char*, ...)’, declared with attribute warn_unused_result [-Wunused-result]
&ax, &ay, &az);
^
[ 12%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CostFunctionFactory.cc.o
[ 14%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/PinholeCamera.cc.o
[ 16%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CataCamera.cc.o
[ 18%] Linking CXX executable /home/ubuntu/vins-ws/devel/lib/benchmark_publisher/benchmark_publisher
[ 20%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/EquidistantCamera.cc.o
[ 20%] Built target benchmark_publisher
[ 22%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/ScaramuzzaCamera.cc.o
[ 25%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/sparse_graph/Transform.cc.o
[ 27%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/gpl/gpl.cc.o
[ 29%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/gpl/EigenQuaternionParameterization.cc.o
[ 31%] Linking CXX shared library /home/ubuntu/vins-ws/devel/lib/libcamera_model.so
[ 31%] Built target camera_model
Scanning dependencies of target ar_demo_node
Scanning dependencies of target feature_tracker
Scanning dependencies of target vins_estimator
[ 35%] Building CXX object VINS-Mono/feature_tracker/CMakeFiles/feature_tracker.dir/src/feature_tracker_node.cpp.o
[ 35%] Building CXX object VINS-Mono/feature_tracker/CMakeFiles/feature_tracker.dir/src/parameters.cpp.o
[ 37%] Building CXX object VINS-Mono/ar_demo/CMakeFiles/ar_demo_node.dir/src/ar_demo_node.cpp.o
[ 39%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator_node.cpp.o
[ 41%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/parameters.cpp.o
[ 47%] Building CXX object VINS-Mono/feature_tracker/CMakeFiles/feature_tracker.dir/src/feature_tracker.cpp.o
[ 47%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator.cpp.o
[ 47%] Linking CXX executable /home/ubuntu/vins-ws/devel/lib/ar_demo/ar_demo_node
[ 47%] Built target ar_demo_node
[ 50%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/feature_manager.cpp.o
c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See file:///usr/share/doc/gcc-5/README.Bugs for instructions.
VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/build.make:62: recipe for target 'VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator_node.cpp.o' failed
make[2]: *** [VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator_node.cpp.o] Error 4
make[2]: *** Waiting for unfinished jobs....
[ 52%] Linking CXX executable /home/ubuntu/vins-ws/devel/lib/feature_tracker/feature_tracker
[ 52%] Built target feature_tracker
CMakeFiles/Makefile2:2166: recipe for target 'VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/all' failed
make[1]: *** [VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

code about last_marginalization_info

Can you provide some clue about last_marginalization_info code.

 if (last_marginalization_info)
        {
            vector<int> drop_set;
            for (int i = 0; i < static_cast<int>(last_marginalization_parameter_blocks.size()); i++)
            {
                if (last_marginalization_parameter_blocks[i] == para_Pose[0] ||
                    last_marginalization_parameter_blocks[i] == para_SpeedBias[0])
                    drop_set.push_back(i);
            }
            // construct new marginlization_factor
            MarginalizationFactor *marginalization_factor = new MarginalizationFactor(last_marginalization_info);
            ResidualBlockInfo *residual_block_info = new ResidualBlockInfo(marginalization_factor, NULL,
                                                                           last_marginalization_parameter_blocks,
                                                                           drop_set);

            marginalization_info->addResidualBlockInfo(residual_block_info);
        }

Why we need to take care of last_marginalization_info. i think we donot need to add a ResidualBlockInfo about last_marginalization_info. Add imu residual and reprojector residual is enough. And in your paper, I cannot find any related to last_marginalization_info.
screenshot from 2017-07-06 19 19 18

Is it related to First Jacobian Estimate, but why we need to fix linearized point(last marginazation process) in next time marginazation.

Changed with my own topic, but it reported an OpenCV error

I changed the topics in file euroc_config_no_extrinsic.yaml and set my camera parameter.
But when iI launch euroc_no_extrinsic_param.launch
It came with an opencv error:

[ INFO] [1497603966.780701533]: init begins
[ INFO] [1497603966.798758974]: Loaded config_file: /home/kevinchow/catkin_ws/src/VINS-Mono/feature_tracker/../config/euroc/euroc_config_no_extrinsic.yaml
[ INFO] [1497603966.810666136]: Loaded vins_folder: /home/kevinchow/catkin_ws/src/VINS-Mono/feature_tracker/../config/../
[ WARN] [1497603966.811355650]: have no prior about extrinsic param, calibrate extrinsic param
[ WARN] [1497603966.811599652]: waiting for image and imu...
[ WARN] [1497603966.854704240]: LOOP_CLOSURE true
voc file: /home/kevinchow/catkin_ws/src/VINS-Mono/feature_tracker/../config/..//support_files/brief_k10L6.bin
loop start load vocabulary
 loop closure init finish
OpenCV Error: Assertion failed (mask.empty() || (mask.type() == CV_8UC1 && mask.size() == image.size())) in goodFeaturesToTrack, file /home/kevinchow/opencv-2.4.10/modules/imgproc/src/featureselect.cpp, line 63
terminate called after throwing an instance of 'cv::Exception'
  what():  /home/kevinchow/opencv-2.4.10/modules/imgproc/src/featureselect.cpp:63: error: (-215) mask.empty() || (mask.type() == CV_8UC1 && mask.size() == image.size()) in function goodFeaturesToTrack

[feature_tracker-1] process has died [pid 10576, exit code -6, cmd /home/kevinchow/catkin_ws/devel/lib/feature_tracker/feature_tracker __name:=feature_tracker __log:=/home/kevinchow/.ros/log/ea0908b8-5242-11e7-a34b-e8039a938798/feature_tracker-1.log].
log file: /home/kevinchow/.ros/log/ea0908b8-5242-11e7-a34b-e8039a938798/feature_tracker-1*.log
^C[vins_estimator-2] killing on exit
terminate called without an active exception
shutting down processing monitor...
... shutting down processing monitor complete
done
kevinchow@kevinchow-Q470-500P4A:~/catkin_ws$ vim /home/kevinchow/opencv-2.4.10/modules/imgproc/src/featureselect.cpp
kevinchow@kevinchow-Q470-500P4A:~/catkin_ws$ /home/kevinchow/catkin_ws/devel/lib/feature_tracker/feature_tracker __name:=feature_tracker __log:=/home/kevinchow/.ros/log/ea0908b8-5242-11e7-a34b-e8039a938798/feature_tracker-1.log
[ INFO] [1497605468.987013289]: Loaded config_file: /home/kevinchow/catkin_ws/src/VINS-Mono/feature_tracker/../config/euroc/euroc_config_no_extrinsic.yaml
[ INFO] [1497605468.988844032]: Loaded vins_folder: /home/kevinchow/catkin_ws/src/VINS-Mono/feature_tracker/../config/../
[ INFO] [1497605468.988985383]: reading paramerter of camera /home/kevinchow/catkin_ws/src/VINS-Mono/feature_tracker/../config/euroc/euroc_config_no_extrinsic.yaml
^Ckevinchow@kevinchow-Q470-500P4A:~/catkin_ws$ 

Can't run vins_rviz.launch successfully

Hi, I'm very glad to see this open-source project and can't wait to run it on my PC. Thanks for your contribution to the community!

But when I run " roslaunch vins_estimator vins_rviz.launch" after another two step("rosbag play xxx.bag" and "roslaunch vins_estimator euroc.launch" ) which have been run successfully, I met an error:

screenshot from 2017-05-24 11 07 45

The node run in the vins_rviz.launch is "rvizvisualisation" which belongs to package rviz, but I can't search the node in my indigo ROS. I replace "rvizvisualisation" with node "rviz", but the same error occured. If I just run "rosrun rviz rviz" by not adding "vins_rviz_config.rviz" , it works. Don't the config file and node "rviz" match each other?
How can I solve this problem? Where can I get the rvizvisualisation node?

Thank you!!!

cannot find where tic is calibrated?

In your paper Monocular Visual-Inertial State Estimation With Online Initialization and Camera-IMU Extrinsic Calibration, you've said that rotation matrix between IMU and Cam is calibrated at first phase, and translation tic is calibrated at second phase. And I've run your code using EuRoC dataset with ESTIMATE_EXTRINSIC set to 2, and the estimator gives an acceptable calibration result for both ric and tic. However, when I read about the code(estimator.cpp), I cannot find the tic's calibration process in anywhere of the code, and can only find process of ric calibraion(shown below).
code

So, could you please tell me where I can find the tic calibration part? Thanks for your excellent work.

Can it work with Kinect V1 + unsynchronized IMU?

The resolution of Kinect V1 is 640*480, with rolling shutter in 30Hz frame rate. And I'm trying to choose IMU supported by ROS, like razor_9dof and DJI A3. Could you give me some advice about the hardware platform of VINS-Mono using Kinect V1?

Thank you in advance!

There is big shift when I used my own sensors

The following picture shows the trajectory generated by VINS-Mono when I moved my camera and IMU rig in the range of 1 square meter.
screenshot from 2017-06-07 15 11 10

What may be the reason for such a big drift?
The IMU I used is Mti, the third generation product of Xsens. The camera I used is Point Grey's Color Blackfly USB 3.0 camera.
I have tried to set the frequency of IMU to 120 Hz and 256 Hz, the max frequency of the Mti IMU, and the frequency of camera to 5 Hz, 10 Hz, 20 Hz, 30 Hz. When the IMU and the camera were set to 256Hz and 5Hz, the best results will get, but the big drift can not avoid through changing the frequency.
I guess there may be several reasons: The camera and IMU are unsynchronized; Camera calibration parameters are not ideal; IMU output data is problematic. What about your opinions?
I observed that you have pointed out that the performance is different on different devices :(global shutter camera + synchronized high-end IMU, e.g. VI-Sensor) > (global shutter camera + synchronized low-end IMU, e.g. camera+DJI A3) > (global camera + unsync high frequency IMU) > (global camera + unsync low frequency IMU) > (rolling camera + unsync low frequency IMU). How big is the difference? Can you provide some degree of expression?

Eigen fail in Odroid u3

Hi! Thank you for make code available!

I have successful run in my labtop but when i try to run at odroid u3, the following error shown up.

[ WARN] [1498578211.335453879]: have no prior about extrinsic param, calibrate extrinsic param
[ WARN] [1498578211.335672337]: waiting for image and imu...
[ WARN] [1498578211.779238376]: throw img, only should happen at the beginning
[ WARN] [1498578211.990729839]: throw img, only should happen at the beginning
[ INFO] [1498578212.191727203]: calibrating extrinsic param, rotation movement is needed
vins_estimator: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h:109: Eigen::internal::plain_array<T, Size, MatrixOrArrayOptions, 16>::plain_array() [with T = double; int Size = 270; int MatrixOrArrayOptions = 0]: Assertion `(reinterpret_cast<size_t>(eigen_unaligned_array_assert_workaround_gcc47(array)) & (15)) == 0 && "this assertion is explained here: " "http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html" " **** READ THIS WEB PAGE !!! ****"' failed.
[vins_estimator-2] process has died [pid 26489, exit code -6, cmd /home/odroid/quad_ws/devel/lib/vins_estimator/vins_estimator /imu0:=/mavros/imu/data __name:=vins_estimator __log:=/home/odroid/.ros/log/f7d626c0-5b47-11e7-91c7-3a02dd67b601/vins_estimator-2.log].
log file: /home/odroid/.ros/log/f7d626c0-5b47-11e7-91c7-3a02dd67b601/vins_estimator-2*.log

How can i fix this? Any advice would be appreciate.
Thank you advanced!

Can't build successfully

I already install the dependency for eigen, ceres, but when I catkin_make, error

[ 4%] Built target benchmark_publisher
[ 6%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/chessboard/Chessboard.cc.o
[ 8%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/calib/CameraCalibration.cc.o
[ 10%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/Camera.cc.o
[ 12%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CameraFactory.cc.o
[ 16%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/EquidistantCamera.cc.o
[ 16%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CostFunctionFactory.cc.o
[ 18%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/PinholeCamera.cc.o
[ 20%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/CataCamera.cc.o
[ 22%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/camera_models/ScaramuzzaCamera.cc.o
[ 25%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/sparse_graph/Transform.cc.o
[ 27%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/gpl/gpl.cc.o
[ 29%] Building CXX object VINS-Mono/camera_model/CMakeFiles/camera_model.dir/src/gpl/EigenQuaternionParameterization.cc.o
[ 31%] Linking CXX shared library /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so
[ 31%] Built target camera_model
[ 35%] Linking CXX executable /home/mc/SLAM/catkin_ws/devel/lib/ar_demo/ar_demo_node
[ 35%] Linking CXX executable /home/mc/SLAM/catkin_ws/devel/lib/feature_tracker/feature_tracker
Scanning dependencies of target vins_estimator
[ 39%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator.cpp.o
[ 39%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/estimator_node.cpp.o
[ 43%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/feature_manager.cpp.o
[ 43%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/parameters.cpp.o
[ 45%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/factor/pose_local_parameterization.cpp.o
[ 47%] Building CXX object VINS-Mono/vins_estimator/CMakeFiles/vins_estimator.dir/src/factor/projection_factor.cpp.o
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::ForVar2()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Solve(ceres::Solver::Options const&, ceres::Problem*, ceres::Solver::Summary*)'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::CheckOpMessageBuilder(char const*)' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to vtable for ceres::CauchyLoss'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::LocalParameterization::~LocalParameterization()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::~CheckOpMessageBuilder()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Solver::Summary::Summary()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::LogMessageFatal::LogMessageFatal(char const*, int, google::CheckOpString const&)'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::NewString()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::AddResidualBlock(ceres::CostFunction*, ceres::LossFunction*, double*, double*, double*)'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::SetParameterization(double*, ceres::LocalParameterization*)' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::~Problem()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::LogMessageFatal::~LogMessageFatal()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Solver::Summary::FullReport() const'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::Problem()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::LogMessage::stream()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::LocalParameterization::MultiplyByJacobian(double const*, int, double const*, double*) const' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to typeinfo for ceres::LocalParameterization'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::LogMessageFatal::LogMessageFatal(char const*, int)' /home/mc/SLAM/catkin_ws/devel/lib/collect2: error: ld returned 1 exit status libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::ForVar2()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Solve(ceres::Solver::Options const&, ceres::Problem*, ceres::Solver::Summary*)' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::CheckOpMessageBuilder(char const*)'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to vtable for ceres::CauchyLoss' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::LocalParameterization::~LocalParameterization()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::~CheckOpMessageBuilder()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Solver::Summary::Summary()'
/home/mc/SLAM/catkin_ws/devel/make[2]: lib/libcamera_model.so:*** [/home/mc/SLAM/catkin_ws/devel/lib/ar_demo/ar_demo_node] Error 1
undefined reference to google::LogMessageFatal::LogMessageFatal(char const*, int, google::CheckOpString const&)' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::base::CheckOpMessageBuilder::NewString()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::AddResidualBlock(ceres::CostFunction*,make[1]: *** [VINS-Mono/ar_demo/CMakeFiles/ar_demo_node.dir/all] Error 2 ceres::LossFunction*, double*, make[1]: double*, double*)' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::SetParameterization(double*, ceres::LocalParameterization*)'
/home/mc/*** Waiting for unfinished jobs....
SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::~Problem()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::LogMessageFatal::~LogMessageFatal()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Solver::Summary::FullReport() const' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::Problem::Problem()'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::LogMessage::stream()' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to ceres::LocalParameterization::MultiplyByJacobian(double const*, int, double const*, double*) const'
/home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to typeinfo for ceres::LocalParameterization' /home/mc/SLAM/catkin_ws/devel/lib/libcamera_model.so: undefined reference to google::LogMessageFatal::LogMessageFatal(char const*, int)'
collect2: error: ld returned 1 exit status
make[2]: *** [/home/mc/SLAM/catkin_ws/devel/lib/feature_tracker/feature_tracker] Error 1
make[1]: *** [VINS-Mono/feature_tracker/CMakeFiles/feature_tracker.dir/all] Error 2

how can I should do

no results when running with my device

Hi, I want to run with my camera and IMU, and I have change the topic name in the config file. However there is no output about position information. And the Rviz shows as:
opencv_orb3

I find that the Global Status is abnormal and it shows: No tf data. Acutual error: Fixed Frame [world] doesn't exist.
So what's the problem and thanks for your help.

question about jacobian

why the matrix Ft in your paper is different from your code?
I can't find out why the Ft in your code is
F.block<3, 3>(0, 0) = Matrix3d::Identity();
F.block<3, 3>(0, 3) = -0.25 * delta_q.toRotationMatrix() * R_a_0_x * _dt * _dt +
-0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * (Matrix3d::Identity() - R_w_x * _dt) * _dt * _dt;
F.block<3, 3>(0, 6) = MatrixXd::Identity(3,3) * _dt;
F.block<3, 3>(0, 9) = -0.25*(delta_q.toRotationMatrix()+result_delta_q.toRotationMatrix()) * _dt * _dt;
F.block<3, 3>(0, 12) = -0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * _dt * -_dt;
F.block<3, 3>(3, 3) = Matrix3d::Identity() - R_w_x * _dt;
F.block<3, 3>(3, 12) = -1.0 * MatrixXd::Identity(3,3) * _dt;
F.block<3, 3>(6, 3) = -0.5 * delta_q.toRotationMatrix() * R_a_0_x * _dt +
-0.5 * result_delta_q.toRotationMatrix()R_a_1_x(Matrix3d::Identity() - R_w_x _dt) _dt;
F.block<3, 3>(6, 6) = Matrix3d::Identity();
F.block<3, 3>(6, 9) = -0.5 * (delta_q.toRotationMatrix() + result_delta_q.toRotationMatrix()) * _dt;
F.block<3, 3>(6, 12) = -0.5 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * -_dt;
F.block<3, 3>(9, 9) = Matrix3d::Identity();
F.block<3, 3>(12, 12) = Matrix3d::Identity();
//cout<<"A"<<endl<<A<<endl;

About hard-coded parameters

Hi,
Thanks for the amazing work. Currently, I am using this code for the initial step to generate tf for my project. One thing I noticed is that FOCAL_LENGTH is hard-coded, and it is assigned 460 in several files. If I use image data from my own camera, should I assume that this value needs to be changed?

Best.
Juncheng

question about the imu frequency

hello, i have some problems about testing the project on device when i launch the euroc_no_extrinsic_param.launch. i use my own imu and rgbd camera. i can see the tracked feature with red points. However , i can not see the pose estimation result and the terminal always remind the "IMU excitation not enouth!". i had calibrate my camera and changed the topic of imu and camera. However, i can not see the tf message. I guess i move the camera without acceleration.i accelerate the camera and then the terminal remind me "unstable features tracking, please slowly move you device!". The frequency of imu is 50HZ and i did not use the static tf to attach imu with camera. Is that the reason causing faliure? Thans for your advices

vins
warning:[ INFO] [1497605197.150036705]: misalign visual structure with IMU
[ INFO] [1497605197.150427043]: IMU excitation not enouth!
[ WARN] [1497605197.271706283]: gyroscope bias initial calibration 0.0121866 0.0426114 0.00346873
[ INFO] [1497605197.273078185]: misalign visual structure with IMU
[ INFO] [1497605197.273471374]: IMU excitation not enouth!
[ WARN] [1497605197.374822350]: gyroscope bias initial calibration 0.000691495 0.03545 -0.00651129
[ INFO] [1497605197.375756768]: misalign visual structure with IMU
[ INFO] [1497605197.376261493]: IMU excitation not enouth!

Rectified Image Shown?

I run some tests and the system performance is quite impressive.
I briefly read the code and I'd like to make sure that the image rectification process is done but the rectified image is not shown on RVIZ, right?

Question about alignment of vector g with world frame?

I guess that at the end of visual inertial alignment(corresponding to function Estimator::visualInitialAlign), shown below:
121

you did the operations described as in your TRO paper:
12131

so I guess rot_diff stands for w_q_c0 in the paper.
Am I correct? And I am a little confused about function Utility::g2R(), it seems that you rule out the influence of yaw in the transform and keep only pitch and roll, what is the reason?
4341341

No trajectory display on rviz gui.

I follow the build steps of VINS-Mono on ROS.
When I play MH_05_difficult.bag, there is no trajectory displaying on rviz gui, just like this:

https://screenshot.net/zh/jqg5puq

There is Global Status:Error. Fixed Frame [world] does not exist.

The result remains the same on MH_x_xxx.bag & VX_X_XXX.bag.
And I found that many people met the same problem,
for example #11

Would you mind giving some advice?

pose graph optimization not always converge

I test the program with EuRoC dataset MH_01_easy, where there exists several loops. And the pose graph optimization iteration times is set to 5(as default), and the keyframe database size is 400(as default). I test for tens of times. Sometimes after a loop is detected and pose graph optimization performed, the drift(e.g. postion) converges to a smaller one than before optimizing; but this does not always happen. There are several times pose graph optimiztion does not converge at all, or converge (to a local optimization I guess) to an unreasonable state with big drift. I want to know why this happen, and how can I get a stabe performance of the loop closure?
1

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.