Compare commits
	
		
			47 Commits
		
	
	
		
			LKcuda
			...
			photometry
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
| 2dac361ba2 | |||
| 0712a98c7f | |||
| 6b8dce9876 | |||
| 49374a4323 | |||
| 3e480560e8 | |||
| b3df525060 | |||
| a8d4580812 | |||
| a0577dfb9d | |||
| 8cfbe06945 | |||
| cab56d9494 | |||
| 5e9149eacc | |||
| e4dbe2f060 | |||
| 6b208dbc44 | |||
| 2ee7c248c1 | |||
| 44de215518 | |||
| ad2f464716 | |||
| 53b26f7613 | |||
| ee40dff740 | |||
| acbcf79417 | |||
| cf40ce8afb | |||
| 750d8ecfb1 | |||
| e3ac604dbf | |||
| e8489dbd06 | |||
| e2e936ff01 | |||
| de07296d31 | |||
| 6ba26d782d | |||
| 821d9d6f71 | |||
| 1ffc4fb37f | |||
| 5958adb57c | |||
| 8defb20c8e | |||
| 1949e4c43d | |||
| 6f16f1b566 | |||
| 1fa2518215 | |||
| d91ff7ca9d | |||
| cfecefe29f | |||
| f4a17f8512 | |||
| 6ae83f0db7 | |||
| 819e43bb3b | |||
| 7f2140ae88 | |||
| 010d36d216 | |||
| abd343f576 | |||
| 8227a8e48d | |||
| a85a4745f2 | |||
| a6af82a269 | |||
| b0dca3b15c | |||
| 79cce26dad | |||
| e6620a4ed4 | 
@@ -24,6 +24,7 @@ find_package(catkin REQUIRED COMPONENTS
 | 
			
		||||
  pcl_conversions
 | 
			
		||||
  pcl_ros
 | 
			
		||||
  std_srvs
 | 
			
		||||
  visualization_msgs
 | 
			
		||||
)
 | 
			
		||||
 | 
			
		||||
## System dependencies are found with CMake's conventions
 | 
			
		||||
@@ -79,6 +80,7 @@ include_directories(
 | 
			
		||||
add_library(msckf_vio
 | 
			
		||||
  src/msckf_vio.cpp
 | 
			
		||||
  src/utils.cpp
 | 
			
		||||
  src/image_handler.cpp
 | 
			
		||||
)
 | 
			
		||||
add_dependencies(msckf_vio
 | 
			
		||||
  ${${PROJECT_NAME}_EXPORTED_TARGETS}
 | 
			
		||||
@@ -87,6 +89,7 @@ add_dependencies(msckf_vio
 | 
			
		||||
target_link_libraries(msckf_vio
 | 
			
		||||
  ${catkin_LIBRARIES}
 | 
			
		||||
  ${SUITESPARSE_LIBRARIES}
 | 
			
		||||
  ${OpenCV_LIBRARIES}
 | 
			
		||||
)
 | 
			
		||||
 | 
			
		||||
# Msckf Vio nodelet
 | 
			
		||||
@@ -106,6 +109,7 @@ target_link_libraries(msckf_vio_nodelet
 | 
			
		||||
add_library(image_processor
 | 
			
		||||
  src/image_processor.cpp
 | 
			
		||||
  src/utils.cpp
 | 
			
		||||
  src/image_handler.cpp
 | 
			
		||||
)
 | 
			
		||||
add_dependencies(image_processor
 | 
			
		||||
  ${${PROJECT_NAME}_EXPORTED_TARGETS}
 | 
			
		||||
 
 | 
			
		||||
							
								
								
									
										36
									
								
								config/camchain-imucam-tum.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										36
									
								
								config/camchain-imucam-tum.yaml
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,36 @@
 | 
			
		||||
cam0:
 | 
			
		||||
  T_cam_imu:
 | 
			
		||||
      [-0.9995378259923383,   0.02917807204183088,  -0.008530798463872679, 0.047094247958417004,
 | 
			
		||||
      0.007526588843243184,   -0.03435493139706542, -0.9993813532126198,   -0.04788273017221637,
 | 
			
		||||
      -0.029453096117288798,  -0.9989836729399656,  0.034119442089241274,  -0.0697294754693238,
 | 
			
		||||
      0.0,                    0.0,                  0.0,                   1.0]
 | 
			
		||||
  camera_model: pinhole
 | 
			
		||||
  distortion_coeffs: [0.010171079892421483, -0.010816440029919381, 0.005942781769412756,
 | 
			
		||||
    -0.001662284667857643]
 | 
			
		||||
  distortion_model: equidistant
 | 
			
		||||
  intrinsics: [380.81042871360756, 380.81194179427075, 510.29465304840727, 514.3304630538506]
 | 
			
		||||
  resolution: [1024, 1024]
 | 
			
		||||
  rostopic: /cam0/image_raw
 | 
			
		||||
cam1:
 | 
			
		||||
  T_cam_imu:
 | 
			
		||||
    [-0.9995240747493029, 0.02986739485347808, -0.007717688852024281, -0.05374086123613335,
 | 
			
		||||
    0.008095979457928231, 0.01256553460985914, -0.9998882749870535, -0.04648588412432889,
 | 
			
		||||
    -0.02976708103202316, -0.9994748851595197, -0.0128013601698453, -0.07333210787623645,
 | 
			
		||||
    0.0, 0.0, 0.0, 1.0]
 | 
			
		||||
  T_cn_cnm1:
 | 
			
		||||
    [0.9999994317488622, -0.0008361847221513937, -0.0006612844045898121, -0.10092123225528335,
 | 
			
		||||
    0.0008042457277382264, 0.9988989443471681, -0.04690684567228134, -0.001964540595211977,
 | 
			
		||||
    0.0006997790813734836, 0.04690628718225568, 0.9988990492196964, -0.0014663556043866572,
 | 
			
		||||
    0.0, 0.0, 0.0, 1.0]
 | 
			
		||||
  camera_model: pinhole
 | 
			
		||||
  distortion_coeffs: [0.01371679169245271, -0.015567360615942622, 0.00905043103315326,
 | 
			
		||||
    -0.002347858896562788]
 | 
			
		||||
  distortion_model: equidistant
 | 
			
		||||
  intrinsics: [379.2869884263036, 379.26583742214524, 505.5666703237407, 510.2840961765407]
 | 
			
		||||
  resolution: [1024, 1024]
 | 
			
		||||
  rostopic: /cam1/image_raw
 | 
			
		||||
T_imu_body:
 | 
			
		||||
  [1.0000, 0.0000, 0.0000, 0.0000,
 | 
			
		||||
  0.0000, 1.0000, 0.0000, 0.0000,
 | 
			
		||||
  0.0000, 0.0000, 1.0000, 0.0000,
 | 
			
		||||
  0.0000, 0.0000, 0.0000, 1.0000]
 | 
			
		||||
@@ -15,6 +15,34 @@
 | 
			
		||||
#include "imu_state.h"
 | 
			
		||||
 | 
			
		||||
namespace msckf_vio {
 | 
			
		||||
 | 
			
		||||
struct Frame{
 | 
			
		||||
  cv::Mat image;
 | 
			
		||||
  double exposureTime_ms;
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
typedef std::map<StateIDType, Frame, std::less<StateIDType>,
 | 
			
		||||
        Eigen::aligned_allocator<
 | 
			
		||||
        std::pair<StateIDType, Frame> > > movingWindow;
 | 
			
		||||
 | 
			
		||||
struct IlluminationParameter{
 | 
			
		||||
  double frame_bias;
 | 
			
		||||
  double frame_gain;
 | 
			
		||||
  double feature_bias;
 | 
			
		||||
  double feature_gain;
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
struct CameraCalibration{
 | 
			
		||||
  std::string distortion_model;
 | 
			
		||||
  cv::Vec2i resolution;
 | 
			
		||||
  cv::Vec4d intrinsics;
 | 
			
		||||
  cv::Vec4d distortion_coeffs;
 | 
			
		||||
  movingWindow moving_window;
 | 
			
		||||
  cv::Mat featureVisu;
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
/*
 | 
			
		||||
 * @brief CAMState Stored camera state in order to
 | 
			
		||||
 *    form measurement model.
 | 
			
		||||
@@ -35,6 +63,9 @@ struct CAMState {
 | 
			
		||||
  // Position of the camera frame in the world frame.
 | 
			
		||||
  Eigen::Vector3d position;
 | 
			
		||||
 | 
			
		||||
  // Illumination Information of the frame
 | 
			
		||||
  IlluminationParameter illumination; 
 | 
			
		||||
 | 
			
		||||
  // These two variables should have the same physical
 | 
			
		||||
  // interpretation with `orientation` and `position`.
 | 
			
		||||
  // There two variables are used to modify the measurement
 | 
			
		||||
 
 | 
			
		||||
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										50
									
								
								include/msckf_vio/image_handler.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										50
									
								
								include/msckf_vio/image_handler.h
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,50 @@
 | 
			
		||||
#ifndef MSCKF_VIO_IMAGE_HANDLER_H
 | 
			
		||||
#define MSCKF_VIO_IMAGE_HANDLER_H
 | 
			
		||||
 | 
			
		||||
#include <vector>
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <opencv2/opencv.hpp>
 | 
			
		||||
#include <opencv2/video.hpp>
 | 
			
		||||
 | 
			
		||||
#include <ros/ros.h>
 | 
			
		||||
#include <cv_bridge/cv_bridge.h>
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
namespace msckf_vio {
 | 
			
		||||
/*
 | 
			
		||||
 * @brief utilities for msckf_vio
 | 
			
		||||
 */
 | 
			
		||||
namespace image_handler {
 | 
			
		||||
 | 
			
		||||
void undistortPoints(
 | 
			
		||||
    const std::vector<cv::Point2f>& pts_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs,
 | 
			
		||||
    std::vector<cv::Point2f>& pts_out,
 | 
			
		||||
    const cv::Matx33d &rectification_matrix = cv::Matx33d::eye(),
 | 
			
		||||
    const cv::Vec4d &new_intrinsics = cv::Vec4d(1,1,0,0));
 | 
			
		||||
 | 
			
		||||
std::vector<cv::Point2f> distortPoints(
 | 
			
		||||
    const std::vector<cv::Point2f>& pts_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs);
 | 
			
		||||
 | 
			
		||||
cv::Point2f distortPoint(
 | 
			
		||||
    const cv::Point2f& pt_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs);
 | 
			
		||||
 | 
			
		||||
void undistortPoint(
 | 
			
		||||
    const cv::Point2f& pt_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs,
 | 
			
		||||
    cv::Point2f& pt_out,
 | 
			
		||||
    const cv::Matx33d &rectification_matrix = cv::Matx33d::eye(),
 | 
			
		||||
    const cv::Vec4d &new_intrinsics = cv::Vec4d(1,1,0,0));
 | 
			
		||||
}
 | 
			
		||||
}
 | 
			
		||||
#endif
 | 
			
		||||
@@ -14,10 +14,6 @@
 | 
			
		||||
#include <opencv2/opencv.hpp>
 | 
			
		||||
#include <opencv2/video.hpp>
 | 
			
		||||
 | 
			
		||||
#include <opencv2/cudaoptflow.hpp>
 | 
			
		||||
#include <opencv2/cudaimgproc.hpp>
 | 
			
		||||
#include <opencv2/cudaarithm.hpp>
 | 
			
		||||
 | 
			
		||||
#include <ros/ros.h>
 | 
			
		||||
#include <cv_bridge/cv_bridge.h>
 | 
			
		||||
#include <image_transport/image_transport.h>
 | 
			
		||||
@@ -26,6 +22,8 @@
 | 
			
		||||
#include <message_filters/subscriber.h>
 | 
			
		||||
#include <message_filters/time_synchronizer.h>
 | 
			
		||||
 | 
			
		||||
#include "cam_state.h"
 | 
			
		||||
 | 
			
		||||
namespace msckf_vio {
 | 
			
		||||
 | 
			
		||||
/*
 | 
			
		||||
@@ -312,7 +310,7 @@ private:
 | 
			
		||||
      const std::vector<unsigned char>& markers,
 | 
			
		||||
      std::vector<T>& refined_vec) {
 | 
			
		||||
    if (raw_vec.size() != markers.size()) {
 | 
			
		||||
      ROS_WARN("The input size of raw_vec(%i) and markers(%i) does not match...",
 | 
			
		||||
      ROS_WARN("The input size of raw_vec(%lu) and markers(%lu) does not match...",
 | 
			
		||||
          raw_vec.size(), markers.size());
 | 
			
		||||
    }
 | 
			
		||||
    for (int i = 0; i < markers.size(); ++i) {
 | 
			
		||||
@@ -336,15 +334,8 @@ private:
 | 
			
		||||
  std::vector<sensor_msgs::Imu> imu_msg_buffer;
 | 
			
		||||
 | 
			
		||||
  // Camera calibration parameters
 | 
			
		||||
  std::string cam0_distortion_model;
 | 
			
		||||
  cv::Vec2i cam0_resolution;
 | 
			
		||||
  cv::Vec4d cam0_intrinsics;
 | 
			
		||||
  cv::Vec4d cam0_distortion_coeffs;
 | 
			
		||||
 | 
			
		||||
  std::string cam1_distortion_model;
 | 
			
		||||
  cv::Vec2i cam1_resolution;
 | 
			
		||||
  cv::Vec4d cam1_intrinsics;
 | 
			
		||||
  cv::Vec4d cam1_distortion_coeffs;
 | 
			
		||||
  CameraCalibration cam0;
 | 
			
		||||
  CameraCalibration cam1;
 | 
			
		||||
 | 
			
		||||
  // Take a vector from cam0 frame to the IMU frame.
 | 
			
		||||
  cv::Matx33d R_cam0_imu;
 | 
			
		||||
@@ -367,13 +358,6 @@ private:
 | 
			
		||||
  boost::shared_ptr<GridFeatures> prev_features_ptr;
 | 
			
		||||
  boost::shared_ptr<GridFeatures> curr_features_ptr;
 | 
			
		||||
 | 
			
		||||
  cv::Ptr<cv::cuda::SparsePyrLKOpticalFlow> d_pyrLK_sparse;
 | 
			
		||||
 | 
			
		||||
  cv::cuda::GpuMat cam0_curr_img;
 | 
			
		||||
  cv::cuda::GpuMat cam1_curr_img;
 | 
			
		||||
  cv::cuda::GpuMat cam0_points_gpu;
 | 
			
		||||
  cv::cuda::GpuMat cam1_points_gpu;
 | 
			
		||||
 | 
			
		||||
  // Number of features after each outlier removal step.
 | 
			
		||||
  int before_tracking;
 | 
			
		||||
  int after_tracking;
 | 
			
		||||
 
 | 
			
		||||
@@ -43,6 +43,50 @@ inline void quaternionNormalize(Eigen::Vector4d& q) {
 | 
			
		||||
  return;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/*
 | 
			
		||||
 * @brief invert rotation of passed quaternion through conjugation
 | 
			
		||||
 *        and return conjugation
 | 
			
		||||
 */
 | 
			
		||||
inline Eigen::Vector4d quaternionConjugate(Eigen::Vector4d& q)
 | 
			
		||||
{
 | 
			
		||||
  Eigen::Vector4d p;
 | 
			
		||||
  p(0) = -q(0);
 | 
			
		||||
  p(1) = -q(1);
 | 
			
		||||
  p(2) = -q(2);
 | 
			
		||||
  p(3) =  q(3);
 | 
			
		||||
  quaternionNormalize(p);
 | 
			
		||||
  return p;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/*
 | 
			
		||||
 * @brief converts a vector4 to a vector3, dropping (3)
 | 
			
		||||
 *        this is typically used to get the vector part of a quaternion
 | 
			
		||||
          for eq small angle approximation
 | 
			
		||||
*/
 | 
			
		||||
inline Eigen::Vector3d v4tov3(const Eigen::Vector4d& q)
 | 
			
		||||
{
 | 
			
		||||
  Eigen::Vector3d p;
 | 
			
		||||
  p(0) = q(0);
 | 
			
		||||
  p(1) = q(1);
 | 
			
		||||
  p(2) = q(2);
 | 
			
		||||
  return p;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/*
 | 
			
		||||
 * @brief Perform q1 * q2
 | 
			
		||||
 */
 | 
			
		||||
 | 
			
		||||
inline Eigen::Vector4d QtoV(const Eigen::Quaterniond& q)
 | 
			
		||||
{
 | 
			
		||||
  Eigen::Vector4d p;
 | 
			
		||||
  p(0) = q.x();
 | 
			
		||||
  p(1) = q.y();
 | 
			
		||||
  p(2) = q.z();
 | 
			
		||||
  p(3) = q.w();
 | 
			
		||||
  return p;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
/*
 | 
			
		||||
 * @brief Perform q1 * q2
 | 
			
		||||
 */
 | 
			
		||||
 
 | 
			
		||||
@@ -14,11 +14,17 @@
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <Eigen/Dense>
 | 
			
		||||
#include <Eigen/Geometry>
 | 
			
		||||
 | 
			
		||||
#include <boost/shared_ptr.hpp>
 | 
			
		||||
#include <opencv2/opencv.hpp>
 | 
			
		||||
#include <opencv2/video.hpp>
 | 
			
		||||
 | 
			
		||||
#include <ros/ros.h>
 | 
			
		||||
#include <sensor_msgs/Imu.h>
 | 
			
		||||
#include <sensor_msgs/Image.h>
 | 
			
		||||
#include <sensor_msgs/PointCloud.h>
 | 
			
		||||
#include <nav_msgs/Odometry.h>
 | 
			
		||||
#include <std_msgs/Float64.h>
 | 
			
		||||
#include <tf/transform_broadcaster.h>
 | 
			
		||||
#include <std_srvs/Trigger.h>
 | 
			
		||||
 | 
			
		||||
@@ -27,6 +33,11 @@
 | 
			
		||||
#include "feature.hpp"
 | 
			
		||||
#include <msckf_vio/CameraMeasurement.h>
 | 
			
		||||
 | 
			
		||||
#include <cv_bridge/cv_bridge.h>
 | 
			
		||||
#include <image_transport/image_transport.h>
 | 
			
		||||
#include <message_filters/subscriber.h>
 | 
			
		||||
#include <message_filters/time_synchronizer.h>
 | 
			
		||||
 | 
			
		||||
namespace msckf_vio {
 | 
			
		||||
/*
 | 
			
		||||
 * @brief MsckfVio Implements the algorithm in
 | 
			
		||||
@@ -97,11 +108,27 @@ class MsckfVio {
 | 
			
		||||
    void imuCallback(const sensor_msgs::ImuConstPtr& msg);
 | 
			
		||||
 | 
			
		||||
    /*
 | 
			
		||||
     * @brief featureCallback
 | 
			
		||||
     *    Callback function for feature measurements.
 | 
			
		||||
     * @param msg Stereo feature measurements.
 | 
			
		||||
     * @brief truthCallback
 | 
			
		||||
     *      Callback function for ground truth navigation information
 | 
			
		||||
     * @param TransformStamped msg
 | 
			
		||||
     */    
 | 
			
		||||
    void truthCallback(
 | 
			
		||||
        const geometry_msgs::TransformStampedPtr& msg);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
    /*
 | 
			
		||||
     * @brief imageCallback
 | 
			
		||||
     *    Callback function for feature measurements
 | 
			
		||||
     *    Triggers measurement update
 | 
			
		||||
     * @param msg
 | 
			
		||||
     *    Camera 0 Image
 | 
			
		||||
     *    Camera 1 Image
 | 
			
		||||
     *    Stereo feature measurements.
 | 
			
		||||
     */
 | 
			
		||||
    void featureCallback(const CameraMeasurementConstPtr& msg);
 | 
			
		||||
    void imageCallback (
 | 
			
		||||
    const sensor_msgs::ImageConstPtr& cam0_img,
 | 
			
		||||
    const sensor_msgs::ImageConstPtr& cam1_img,
 | 
			
		||||
    const CameraMeasurementConstPtr& feature_msg);
 | 
			
		||||
 | 
			
		||||
    /*
 | 
			
		||||
     * @brief publish Publish the results of VIO.
 | 
			
		||||
@@ -126,6 +153,26 @@ class MsckfVio {
 | 
			
		||||
    bool resetCallback(std_srvs::Trigger::Request& req,
 | 
			
		||||
        std_srvs::Trigger::Response& res);
 | 
			
		||||
 | 
			
		||||
    // Saves the exposure time and the camera measurementes
 | 
			
		||||
    void manageMovingWindow(
 | 
			
		||||
        const sensor_msgs::ImageConstPtr& cam0_img,
 | 
			
		||||
        const sensor_msgs::ImageConstPtr& cam1_img,
 | 
			
		||||
        const CameraMeasurementConstPtr& feature_msg);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
    void calcErrorState();
 | 
			
		||||
 | 
			
		||||
    // Debug related Functions
 | 
			
		||||
    // Propagate the true state
 | 
			
		||||
    void batchTruthProcessing(
 | 
			
		||||
        const double& time_bound);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
    void processTruthtoIMU(const double& time,
 | 
			
		||||
        const Eigen::Vector4d& m_rot,
 | 
			
		||||
        const Eigen::Vector3d& m_trans);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
    // Filter related functions
 | 
			
		||||
    // Propogate the state
 | 
			
		||||
    void batchImuProcessing(
 | 
			
		||||
@@ -137,21 +184,39 @@ class MsckfVio {
 | 
			
		||||
        const Eigen::Vector3d& gyro,
 | 
			
		||||
        const Eigen::Vector3d& acc);
 | 
			
		||||
 | 
			
		||||
    // groundtruth state augmentation
 | 
			
		||||
    void truePhotometricStateAugmentation(const double& time);
 | 
			
		||||
 | 
			
		||||
    // Measurement update
 | 
			
		||||
    void stateAugmentation(const double& time);
 | 
			
		||||
    void PhotometricStateAugmentation(const double& time);
 | 
			
		||||
    void addFeatureObservations(const CameraMeasurementConstPtr& msg);
 | 
			
		||||
    // This function is used to compute the measurement Jacobian
 | 
			
		||||
    // for a single feature observed at a single camera frame.
 | 
			
		||||
    void measurementJacobian(const StateIDType& cam_state_id,
 | 
			
		||||
        const FeatureIDType& feature_id,
 | 
			
		||||
        Eigen::Matrix<double, 4, 6>& H_x,
 | 
			
		||||
        Eigen::Matrix<double, 4, 3>& H_f,
 | 
			
		||||
        Eigen::Vector4d& r);
 | 
			
		||||
        Eigen::Matrix<double, 2, 6>& H_x,
 | 
			
		||||
        Eigen::Matrix<double, 2, 3>& H_f,
 | 
			
		||||
        Eigen::Vector2d& r);
 | 
			
		||||
    // This function computes the Jacobian of all measurements viewed
 | 
			
		||||
    // in the given camera states of this feature.
 | 
			
		||||
    void featureJacobian(const FeatureIDType& feature_id,
 | 
			
		||||
        const std::vector<StateIDType>& cam_state_ids,
 | 
			
		||||
        Eigen::MatrixXd& H_x, Eigen::VectorXd& r);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
    void PhotometricMeasurementJacobian(
 | 
			
		||||
    const StateIDType& cam_state_id,
 | 
			
		||||
    const FeatureIDType& feature_id,
 | 
			
		||||
    Eigen::MatrixXd& H_x,
 | 
			
		||||
    Eigen::MatrixXd& H_y,
 | 
			
		||||
    Eigen::VectorXd& r);
 | 
			
		||||
 | 
			
		||||
    void PhotometricFeatureJacobian(
 | 
			
		||||
    const FeatureIDType& feature_id,
 | 
			
		||||
    const std::vector<StateIDType>& cam_state_ids,
 | 
			
		||||
    Eigen::MatrixXd& H_x, Eigen::VectorXd& r);
 | 
			
		||||
 | 
			
		||||
    void measurementUpdate(const Eigen::MatrixXd& H,
 | 
			
		||||
        const Eigen::VectorXd& r);
 | 
			
		||||
    bool gatingTest(const Eigen::MatrixXd& H,
 | 
			
		||||
@@ -163,11 +228,32 @@ class MsckfVio {
 | 
			
		||||
    // Reset the system online if the uncertainty is too large.
 | 
			
		||||
    void onlineReset();
 | 
			
		||||
 | 
			
		||||
    // Photometry flag
 | 
			
		||||
    bool PHOTOMETRIC;
 | 
			
		||||
 | 
			
		||||
    // debug flag
 | 
			
		||||
    bool PRINTIMAGES;
 | 
			
		||||
    bool GROUNDTRUTH;
 | 
			
		||||
 | 
			
		||||
    bool nan_flag;
 | 
			
		||||
    bool play;
 | 
			
		||||
    double last_time_bound;
 | 
			
		||||
 | 
			
		||||
    // Patch size for Photometry
 | 
			
		||||
    int N;
 | 
			
		||||
 | 
			
		||||
    // Chi squared test table.
 | 
			
		||||
    static std::map<int, double> chi_squared_test_table;
 | 
			
		||||
 | 
			
		||||
    // State vector
 | 
			
		||||
    StateServer state_server;
 | 
			
		||||
 | 
			
		||||
    // Ground truth state vector 
 | 
			
		||||
    StateServer true_state_server;
 | 
			
		||||
 | 
			
		||||
    // error state based on ground truth
 | 
			
		||||
    StateServer err_state_server;
 | 
			
		||||
 | 
			
		||||
    // Maximum number of camera states
 | 
			
		||||
    int max_cam_state_size;
 | 
			
		||||
 | 
			
		||||
@@ -179,6 +265,22 @@ class MsckfVio {
 | 
			
		||||
    // transfer delay between IMU and Image messages.
 | 
			
		||||
    std::vector<sensor_msgs::Imu> imu_msg_buffer;
 | 
			
		||||
 | 
			
		||||
    // Ground Truth message data
 | 
			
		||||
    std::vector<geometry_msgs::TransformStamped> truth_msg_buffer;
 | 
			
		||||
    // Moving Window buffer
 | 
			
		||||
    movingWindow cam0_moving_window;
 | 
			
		||||
    movingWindow cam1_moving_window;
 | 
			
		||||
 | 
			
		||||
    // Camera calibration parameters
 | 
			
		||||
    CameraCalibration cam0;
 | 
			
		||||
    CameraCalibration cam1;
 | 
			
		||||
 | 
			
		||||
    // covariance data
 | 
			
		||||
    double irradiance_frame_bias;
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
    ros::Time image_save_time;
 | 
			
		||||
 | 
			
		||||
    // Indicate if the gravity vector is set.
 | 
			
		||||
    bool is_gravity_set;
 | 
			
		||||
 | 
			
		||||
@@ -206,12 +308,20 @@ class MsckfVio {
 | 
			
		||||
 | 
			
		||||
    // Subscribers and publishers
 | 
			
		||||
    ros::Subscriber imu_sub;
 | 
			
		||||
    ros::Subscriber feature_sub;
 | 
			
		||||
    ros::Subscriber truth_sub;
 | 
			
		||||
    ros::Publisher odom_pub;
 | 
			
		||||
    ros::Publisher marker_pub;
 | 
			
		||||
    ros::Publisher feature_pub;
 | 
			
		||||
    tf::TransformBroadcaster tf_pub;
 | 
			
		||||
    ros::ServiceServer reset_srv;
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
    message_filters::Subscriber<sensor_msgs::Image> cam0_img_sub;
 | 
			
		||||
    message_filters::Subscriber<sensor_msgs::Image> cam1_img_sub;
 | 
			
		||||
    message_filters::Subscriber<CameraMeasurement> feature_sub;
 | 
			
		||||
 | 
			
		||||
    message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image, CameraMeasurement> image_sub;
 | 
			
		||||
    
 | 
			
		||||
    // Frame id
 | 
			
		||||
    std::string fixed_frame_id;
 | 
			
		||||
    std::string child_frame_id;
 | 
			
		||||
@@ -232,6 +342,9 @@ class MsckfVio {
 | 
			
		||||
    ros::Publisher mocap_odom_pub;
 | 
			
		||||
    geometry_msgs::TransformStamped raw_mocap_odom_msg;
 | 
			
		||||
    Eigen::Isometry3d mocap_initial_frame;
 | 
			
		||||
 | 
			
		||||
    Eigen::Vector4d mocap_initial_orientation;
 | 
			
		||||
    Eigen::Vector3d mocap_initial_position;
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
typedef MsckfVio::Ptr MsckfVioPtr;
 | 
			
		||||
 
 | 
			
		||||
@@ -11,9 +11,6 @@
 | 
			
		||||
#include <ros/ros.h>
 | 
			
		||||
#include <string>
 | 
			
		||||
#include <opencv2/core/core.hpp>
 | 
			
		||||
#include <opencv2/cudaoptflow.hpp>
 | 
			
		||||
#include <opencv2/cudaimgproc.hpp>
 | 
			
		||||
#include <opencv2/cudaarithm.hpp>
 | 
			
		||||
#include <Eigen/Geometry>
 | 
			
		||||
 | 
			
		||||
namespace msckf_vio {
 | 
			
		||||
@@ -21,10 +18,6 @@ namespace msckf_vio {
 | 
			
		||||
 * @brief utilities for msckf_vio
 | 
			
		||||
 */
 | 
			
		||||
namespace utils {
 | 
			
		||||
 | 
			
		||||
void download(const cv::cuda::GpuMat& d_mat, std::vector<uchar>& vec);
 | 
			
		||||
void download(const cv::cuda::GpuMat& d_mat, std::vector<cv::Point2f>& vec);
 | 
			
		||||
 | 
			
		||||
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
 | 
			
		||||
                                    const std::string &field);
 | 
			
		||||
 | 
			
		||||
 
 | 
			
		||||
@@ -8,7 +8,8 @@
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="image_processor"
 | 
			
		||||
      args="standalone msckf_vio/ImageProcessorNodelet"
 | 
			
		||||
      output="screen">
 | 
			
		||||
      output="screen"
 | 
			
		||||
       >
 | 
			
		||||
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
      <param name="grid_row" value="4"/>
 | 
			
		||||
 
 | 
			
		||||
							
								
								
									
										33
									
								
								launch/image_processor_mynt.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										33
									
								
								launch/image_processor_mynt.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,33 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="firefly_sbx"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-mynt.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="image_processor"
 | 
			
		||||
      args="standalone msckf_vio/ImageProcessorNodelet"
 | 
			
		||||
      output="screen">
 | 
			
		||||
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
      <param name="grid_row" value="4"/>
 | 
			
		||||
      <param name="grid_col" value="5"/>
 | 
			
		||||
      <param name="grid_min_feature_num" value="3"/>
 | 
			
		||||
      <param name="grid_max_feature_num" value="4"/>
 | 
			
		||||
      <param name="pyramid_levels" value="3"/>
 | 
			
		||||
      <param name="patch_size" value="15"/>
 | 
			
		||||
      <param name="fast_threshold" value="10"/>
 | 
			
		||||
      <param name="max_iteration" value="30"/>
 | 
			
		||||
      <param name="track_precision" value="0.01"/>
 | 
			
		||||
      <param name="ransac_threshold" value="3"/>
 | 
			
		||||
      <param name="stereo_threshold" value="5"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="/imu0"/>
 | 
			
		||||
      <remap from="~cam0_image" to="/mynteye/left/image_raw"/>
 | 
			
		||||
      <remap from="~cam1_image" to="/mynteye/right/image_raw"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
							
								
								
									
										34
									
								
								launch/image_processor_tum.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										34
									
								
								launch/image_processor_tum.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,34 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="firefly_sbx"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-tum.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="image_processor"
 | 
			
		||||
      args="standalone msckf_vio/ImageProcessorNodelet"
 | 
			
		||||
      output="screen"
 | 
			
		||||
       >
 | 
			
		||||
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
      <param name="grid_row" value="4"/>
 | 
			
		||||
      <param name="grid_col" value="4"/>
 | 
			
		||||
      <param name="grid_min_feature_num" value="3"/>
 | 
			
		||||
      <param name="grid_max_feature_num" value="4"/>
 | 
			
		||||
      <param name="pyramid_levels" value="3"/>
 | 
			
		||||
      <param name="patch_size" value="15"/>
 | 
			
		||||
      <param name="fast_threshold" value="10"/>
 | 
			
		||||
      <param name="max_iteration" value="30"/>
 | 
			
		||||
      <param name="track_precision" value="0.01"/>
 | 
			
		||||
      <param name="ransac_threshold" value="3"/>
 | 
			
		||||
      <param name="stereo_threshold" value="5"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="/imu0"/>
 | 
			
		||||
      <remap from="~cam0_image" to="/cam0/image_raw"/>
 | 
			
		||||
      <remap from="~cam1_image" to="/cam1/image_raw"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
							
								
								
									
										75
									
								
								launch/msckf_vio_debug_tum.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										75
									
								
								launch/msckf_vio_debug_tum.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,75 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="firefly_sbx"/>
 | 
			
		||||
  <arg name="fixed_frame_id" default="world"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-tum.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <include file="$(find msckf_vio)/launch/image_processor_tum.launch">
 | 
			
		||||
    <arg name="robot" value="$(arg robot)"/>
 | 
			
		||||
    <arg name="calibration_file" value="$(arg calibration_file)"/>
 | 
			
		||||
  </include>
 | 
			
		||||
 | 
			
		||||
  <!-- Msckf Vio Nodelet  -->
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="vio"
 | 
			
		||||
      args='standalone msckf_vio/MsckfVioNodelet'
 | 
			
		||||
      output="screen"
 | 
			
		||||
      launch-prefix="xterm -e gdb --args">
 | 
			
		||||
 | 
			
		||||
      <!-- Photometry Flag-->
 | 
			
		||||
      <param name="PHOTOMETRIC" value="true"/>
 | 
			
		||||
 | 
			
		||||
      <!-- Debugging Flaggs -->
 | 
			
		||||
      <param name="PrintImages" value="true"/>
 | 
			
		||||
      <param name="GroundTruth" value="false"/>
 | 
			
		||||
 | 
			
		||||
      <param name="patch_size_n" value="7"/>
 | 
			
		||||
 | 
			
		||||
      <!-- Calibration parameters -->
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
 | 
			
		||||
      <param name="publish_tf" value="true"/>
 | 
			
		||||
      <param name="frame_rate" value="20"/>
 | 
			
		||||
      <param name="fixed_frame_id" value="$(arg fixed_frame_id)"/>
 | 
			
		||||
      <param name="child_frame_id" value="odom"/>
 | 
			
		||||
      <param name="max_cam_state_size" value="20"/>
 | 
			
		||||
      <param name="position_std_threshold" value="8.0"/>
 | 
			
		||||
 | 
			
		||||
      <param name="rotation_threshold" value="0.2618"/>
 | 
			
		||||
      <param name="translation_threshold" value="0.4"/>
 | 
			
		||||
      <param name="tracking_rate_threshold" value="0.5"/>
 | 
			
		||||
 | 
			
		||||
      <!-- Feature optimization config -->
 | 
			
		||||
      <param name="feature/config/translation_threshold" value="-1.0"/>
 | 
			
		||||
 | 
			
		||||
      <!-- These values should be standard deviation -->
 | 
			
		||||
      <param name="noise/gyro" value="0.005"/>
 | 
			
		||||
      <param name="noise/acc" value="0.05"/>
 | 
			
		||||
      <param name="noise/gyro_bias" value="0.001"/>
 | 
			
		||||
      <param name="noise/acc_bias" value="0.01"/>
 | 
			
		||||
      <param name="noise/feature" value="0.035"/>
 | 
			
		||||
 | 
			
		||||
      <param name="initial_state/velocity/x" value="0.0"/>
 | 
			
		||||
      <param name="initial_state/velocity/y" value="0.0"/>
 | 
			
		||||
      <param name="initial_state/velocity/z" value="0.0"/>
 | 
			
		||||
 | 
			
		||||
      <!-- These values should be covariance -->
 | 
			
		||||
      <param name="initial_covariance/velocity" value="0.25"/>
 | 
			
		||||
      <param name="initial_covariance/gyro_bias" value="0.01"/>
 | 
			
		||||
      <param name="initial_covariance/acc_bias" value="0.01"/>
 | 
			
		||||
      <param name="initial_covariance/extrinsic_rotation_cov" value="3.0462e-4"/>
 | 
			
		||||
      <param name="initial_covariance/extrinsic_translation_cov" value="2.5e-5"/>
 | 
			
		||||
      <param name="initial_covariance/irradiance_frame_bias" value="0.1"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="/imu0"/>
 | 
			
		||||
      <remap from="~cam0_image" to="/cam0/image_raw"/>
 | 
			
		||||
      <remap from="~cam1_image" to="/cam1/image_raw"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~features" to="image_processor/features"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
@@ -53,6 +53,9 @@
 | 
			
		||||
      <param name="initial_covariance/extrinsic_translation_cov" value="2.5e-5"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="/imu0"/>
 | 
			
		||||
      <remap from="~cam0_image" to="/cam0/image_raw"/>
 | 
			
		||||
      <remap from="~cam1_image" to="/cam1/image_raw"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~features" to="image_processor/features"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
 
 | 
			
		||||
							
								
								
									
										61
									
								
								launch/msckf_vio_mynt.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										61
									
								
								launch/msckf_vio_mynt.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,61 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="firefly_sbx"/>
 | 
			
		||||
  <arg name="fixed_frame_id" default="world"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-mynt.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <include file="$(find msckf_vio)/launch/image_processor_mynt.launch">
 | 
			
		||||
    <arg name="robot" value="$(arg robot)"/>
 | 
			
		||||
    <arg name="calibration_file" value="$(arg calibration_file)"/>
 | 
			
		||||
  </include>
 | 
			
		||||
 | 
			
		||||
  <!-- Msckf Vio Nodelet  -->
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="vio"
 | 
			
		||||
      args='standalone msckf_vio/MsckfVioNodelet'
 | 
			
		||||
      output="screen">
 | 
			
		||||
 | 
			
		||||
      <!-- Calibration parameters -->
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
 | 
			
		||||
      <param name="publish_tf" value="true"/>
 | 
			
		||||
      <param name="frame_rate" value="20"/>
 | 
			
		||||
      <param name="fixed_frame_id" value="$(arg fixed_frame_id)"/>
 | 
			
		||||
      <param name="child_frame_id" value="odom"/>
 | 
			
		||||
      <param name="max_cam_state_size" value="20"/>
 | 
			
		||||
      <param name="position_std_threshold" value="8.0"/>
 | 
			
		||||
 | 
			
		||||
      <param name="rotation_threshold" value="0.2618"/>
 | 
			
		||||
      <param name="translation_threshold" value="0.4"/>
 | 
			
		||||
      <param name="tracking_rate_threshold" value="0.5"/>
 | 
			
		||||
 | 
			
		||||
      <!-- Feature optimization config -->
 | 
			
		||||
      <param name="feature/config/translation_threshold" value="-1.0"/>
 | 
			
		||||
 | 
			
		||||
      <!-- These values should be standard deviation -->
 | 
			
		||||
      <param name="noise/gyro" value="0.005"/>
 | 
			
		||||
      <param name="noise/acc" value="0.05"/>
 | 
			
		||||
      <param name="noise/gyro_bias" value="0.001"/>
 | 
			
		||||
      <param name="noise/acc_bias" value="0.01"/>
 | 
			
		||||
      <param name="noise/feature" value="0.035"/>
 | 
			
		||||
 | 
			
		||||
      <param name="initial_state/velocity/x" value="0.0"/>
 | 
			
		||||
      <param name="initial_state/velocity/y" value="0.0"/>
 | 
			
		||||
      <param name="initial_state/velocity/z" value="0.0"/>
 | 
			
		||||
 | 
			
		||||
      <!-- These values should be covariance -->
 | 
			
		||||
      <param name="initial_covariance/velocity" value="0.25"/>
 | 
			
		||||
      <param name="initial_covariance/gyro_bias" value="0.01"/>
 | 
			
		||||
      <param name="initial_covariance/acc_bias" value="0.01"/>
 | 
			
		||||
      <param name="initial_covariance/extrinsic_rotation_cov" value="3.0462e-4"/>
 | 
			
		||||
      <param name="initial_covariance/extrinsic_translation_cov" value="2.5e-5"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="/mynteye/imu/data_raw"/>
 | 
			
		||||
      <remap from="~features" to="image_processor/features"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
							
								
								
									
										74
									
								
								launch/msckf_vio_tum.launch
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										74
									
								
								launch/msckf_vio_tum.launch
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,74 @@
 | 
			
		||||
<launch>
 | 
			
		||||
 | 
			
		||||
  <arg name="robot" default="firefly_sbx"/>
 | 
			
		||||
  <arg name="fixed_frame_id" default="world"/>
 | 
			
		||||
  <arg name="calibration_file"
 | 
			
		||||
    default="$(find msckf_vio)/config/camchain-imucam-tum.yaml"/>
 | 
			
		||||
 | 
			
		||||
  <!-- Image Processor Nodelet  -->
 | 
			
		||||
  <include file="$(find msckf_vio)/launch/image_processor_tum.launch">
 | 
			
		||||
    <arg name="robot" value="$(arg robot)"/>
 | 
			
		||||
    <arg name="calibration_file" value="$(arg calibration_file)"/>
 | 
			
		||||
  </include>
 | 
			
		||||
 | 
			
		||||
  <!-- Msckf Vio Nodelet  -->
 | 
			
		||||
  <group ns="$(arg robot)">
 | 
			
		||||
    <node pkg="nodelet" type="nodelet" name="vio"
 | 
			
		||||
      args='standalone msckf_vio/MsckfVioNodelet'
 | 
			
		||||
      output="screen">
 | 
			
		||||
 | 
			
		||||
      <!-- Photometry Flag-->
 | 
			
		||||
      <param name="PHOTOMETRIC" value="true"/>
 | 
			
		||||
 | 
			
		||||
      <!-- Debugging Flaggs -->
 | 
			
		||||
      <param name="PrintImages" value="true"/>
 | 
			
		||||
      <param name="GroundTruth" value="false"/>
 | 
			
		||||
 | 
			
		||||
      <param name="patch_size_n" value="1"/>
 | 
			
		||||
      <!-- Calibration parameters -->
 | 
			
		||||
      <rosparam command="load" file="$(arg calibration_file)"/>
 | 
			
		||||
 | 
			
		||||
      <param name="publish_tf" value="true"/>
 | 
			
		||||
      <param name="frame_rate" value="20"/>
 | 
			
		||||
      <param name="fixed_frame_id" value="$(arg fixed_frame_id)"/>
 | 
			
		||||
      <param name="child_frame_id" value="odom"/>
 | 
			
		||||
      <param name="max_cam_state_size" value="20"/>
 | 
			
		||||
      <param name="position_std_threshold" value="8.0"/>
 | 
			
		||||
 | 
			
		||||
      <param name="rotation_threshold" value="0.2618"/>
 | 
			
		||||
      <param name="translation_threshold" value="0.4"/>
 | 
			
		||||
      <param name="tracking_rate_threshold" value="0.5"/>
 | 
			
		||||
 | 
			
		||||
      <!-- Feature optimization config -->
 | 
			
		||||
      <param name="feature/config/translation_threshold" value="-1.0"/>
 | 
			
		||||
 | 
			
		||||
      <!-- These values should be standard deviation -->
 | 
			
		||||
      <param name="noise/gyro" value="0.005"/>
 | 
			
		||||
      <param name="noise/acc" value="0.05"/>
 | 
			
		||||
      <param name="noise/gyro_bias" value="0.001"/>
 | 
			
		||||
      <param name="noise/acc_bias" value="0.01"/>
 | 
			
		||||
      <param name="noise/feature" value="0.035"/>
 | 
			
		||||
 | 
			
		||||
      <param name="initial_state/velocity/x" value="0.0"/>
 | 
			
		||||
      <param name="initial_state/velocity/y" value="0.0"/>
 | 
			
		||||
      <param name="initial_state/velocity/z" value="0.0"/>
 | 
			
		||||
 | 
			
		||||
      <!-- These values should be covariance -->
 | 
			
		||||
      <param name="initial_covariance/velocity" value="0.25"/>
 | 
			
		||||
      <param name="initial_covariance/gyro_bias" value="0.01"/>
 | 
			
		||||
      <param name="initial_covariance/acc_bias" value="0.01"/>
 | 
			
		||||
      <param name="initial_covariance/extrinsic_rotation_cov" value="3.0462e-4"/>
 | 
			
		||||
      <param name="initial_covariance/extrinsic_translation_cov" value="2.5e-5"/>
 | 
			
		||||
      <param name="initial_covariance/irradiance_frame_bias" value="0.1"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~imu" to="/imu0"/>
 | 
			
		||||
      <remap from="~ground_truth" to="/vrpn_client/raw_transform"/>
 | 
			
		||||
      <remap from="~cam0_image" to="/cam0/image_raw"/>
 | 
			
		||||
      <remap from="~cam1_image" to="/cam1/image_raw"/>
 | 
			
		||||
 | 
			
		||||
      <remap from="~features" to="image_processor/features"/>
 | 
			
		||||
 | 
			
		||||
    </node>
 | 
			
		||||
  </group>
 | 
			
		||||
 | 
			
		||||
</launch>
 | 
			
		||||
@@ -1,4 +1,4 @@
 | 
			
		||||
std_msgs/Header header
 | 
			
		||||
Header header
 | 
			
		||||
# All features on the current image,
 | 
			
		||||
# including tracked ones and newly detected ones.
 | 
			
		||||
FeatureMeasurement[] features
 | 
			
		||||
 
 | 
			
		||||
@@ -3,13 +3,12 @@
 | 
			
		||||
 | 
			
		||||
  <name>msckf_vio</name>
 | 
			
		||||
  <version>0.0.1</version>
 | 
			
		||||
  <description>Multi-State Constraint Kalman Filter for Vision-aided Inertial Navigation</description>
 | 
			
		||||
  <description>Multi-State Constraint Kalman Filter - Photometric expansion</description>
 | 
			
		||||
 | 
			
		||||
  <maintainer email="sunke.polyu@gmail.com">Ke Sun</maintainer>
 | 
			
		||||
  <maintainer email="raphael@maenle.net">Raphael Maenle</maintainer>
 | 
			
		||||
  <license>Penn Software License</license>
 | 
			
		||||
 | 
			
		||||
  <author email="sunke.polyu@gmail.com">Ke Sun</author>
 | 
			
		||||
  <author email="kartikmohta@gmail.com">Kartik Mohta</author>
 | 
			
		||||
  <author email="raphael@maenle.net">Raphael Maenle</author>
 | 
			
		||||
 | 
			
		||||
  <buildtool_depend>catkin</buildtool_depend>
 | 
			
		||||
 | 
			
		||||
@@ -19,6 +18,7 @@
 | 
			
		||||
  <depend>nav_msgs</depend>
 | 
			
		||||
  <depend>sensor_msgs</depend>
 | 
			
		||||
  <depend>geometry_msgs</depend>
 | 
			
		||||
  <depend>visualization_msgs</depend>
 | 
			
		||||
  <depend>eigen_conversions</depend>
 | 
			
		||||
  <depend>tf_conversions</depend>
 | 
			
		||||
  <depend>random_numbers</depend>
 | 
			
		||||
 
 | 
			
		||||
							
								
								
									
										97
									
								
								pseudocode/pseudocode_image_processing
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										97
									
								
								pseudocode/pseudocode_image_processing
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,97 @@
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
stereo callback()
 | 
			
		||||
 | 
			
		||||
	create image pyramids
 | 
			
		||||
		_Constructs the image pyramid which can be passed to calcOpticalFlowPyrLK._
 | 
			
		||||
.
 | 
			
		||||
	if first Frame:
 | 
			
		||||
		*initialize first Frame ()
 | 
			
		||||
 | 
			
		||||
	else:
 | 
			
		||||
		*track Features ()
 | 
			
		||||
 | 
			
		||||
		*addnewFeatures ()
 | 
			
		||||
 | 
			
		||||
		*pruneGridFeatures()
 | 
			
		||||
			_removes worst features from any overflowing grid_
 | 
			
		||||
 | 
			
		||||
	publish features (u1, v1, u2, v2)
 | 
			
		||||
		_undistorts them beforehand_
 | 
			
		||||
 | 
			
		||||
addnewFeatures()
 | 
			
		||||
	*mask existing features
 | 
			
		||||
	*detect new fast features
 | 
			
		||||
	*collect in a grid, keep only best n per grid
 | 
			
		||||
	*stereomatch()
 | 
			
		||||
	*save inliers into a new feature with u,v on cam0 and cam1
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
track Features()
 | 
			
		||||
	*integrateIMUData ()
 | 
			
		||||
		_uses existing IMU data between two frames to calc. rotation between the two frames_
 | 
			
		||||
 | 
			
		||||
	*predictFeatureTracking()
 | 
			
		||||
		_compensates the rotation between consecutive frames - rotates previous camera frame features to current camera rotation_
 | 
			
		||||
 | 
			
		||||
	*calcOpticalFlowPyrLK()
 | 
			
		||||
		_measures the change between the features in the previous frame and in the current frame (using the predicted features)_
 | 
			
		||||
 | 
			
		||||
	*remove points outside of image region
 | 
			
		||||
		_how does this even happen?_
 | 
			
		||||
 | 
			
		||||
	*stereo match()
 | 
			
		||||
		_find tracked features from optical flow in the camera 1 image_
 | 
			
		||||
		_remove all features that could not be matched_
 | 
			
		||||
 | 
			
		||||
	*twoPointRansac(cam0)
 | 
			
		||||
	*twoPointRansac(cam1)
 | 
			
		||||
		_remove any features outside best found ransac model_
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
twoPointRansac()
 | 
			
		||||
	*mark all points as inliers
 | 
			
		||||
	*compensate rotation between frames
 | 
			
		||||
	*normalize points
 | 
			
		||||
	*calculate difference bewteen previous and current points
 | 
			
		||||
	*mark large distances (over 50 pixels currently)
 | 
			
		||||
	*calculate mean points distance
 | 
			
		||||
	*return if inliers (non marked) < 3
 | 
			
		||||
	*return if motion smaller than norm pixel unit
 | 
			
		||||
	*ransac
 | 
			
		||||
		*optimize with found inlier after random sample
 | 
			
		||||
 | 
			
		||||
	*set inlier markers
 | 
			
		||||
 | 
			
		||||
initialize first Frame()
 | 
			
		||||
 | 
			
		||||
	features = FastFeatureDetector detect ()
 | 
			
		||||
 | 
			
		||||
	*stereo match ()
 | 
			
		||||
 | 
			
		||||
	group features into grid
 | 
			
		||||
		- according to position in the image
 | 
			
		||||
		- sorting them by response
 | 
			
		||||
		- save the top responses
 | 
			
		||||
		- save the top responses
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
stereo match ()
 | 
			
		||||
 | 
			
		||||
	*undistort cam0 Points
 | 
			
		||||
	*project cam0 Points to cam1 to initialize points in cam1
 | 
			
		||||
 | 
			
		||||
	*calculate lk optical flow
 | 
			
		||||
		_used because camera calibrations not perfect enough_
 | 
			
		||||
		_also, calculation more efficient, because LK calculated anyway_
 | 
			
		||||
 | 
			
		||||
	*compute relative trans/rot between cam0 and cam1*
 | 
			
		||||
 | 
			
		||||
	*remove outliers based on essential matrix
 | 
			
		||||
		_essential matrix relates points in stereo image (pinhole model)_
 | 
			
		||||
		for every point:
 | 
			
		||||
			- calculate epipolar line of point in cam0
 | 
			
		||||
			- calculate error of cam1 to epipolar line 
 | 
			
		||||
			- remove if to big
 | 
			
		||||
							
								
								
									
										82
									
								
								pseudocode/pseudocode_msckf
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										82
									
								
								pseudocode/pseudocode_msckf
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,82 @@
 | 
			
		||||
featureCallback
 | 
			
		||||
	propagate IMU state()
 | 
			
		||||
	state Augmentation()
 | 
			
		||||
	add Feature Observations()
 | 
			
		||||
 | 
			
		||||
	#the following possibly trigger ekf update step:
 | 
			
		||||
	remove Lost Features ()
 | 
			
		||||
	prune Camera State Buffer ()
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
remove Lost Features()
 | 
			
		||||
	every feature that does not have a current observation:
 | 
			
		||||
		*just delete if not enough features
 | 
			
		||||
 | 
			
		||||
		check Motion of Feature ()
 | 
			
		||||
			_calculation here makes no sense - he uses pixel position as direction vector for feature?_
 | 
			
		||||
		*initialize Position ()
 | 
			
		||||
 | 
			
		||||
		caculate feature Jakobian and Residual()
 | 
			
		||||
			*for every observation in this feature
 | 
			
		||||
				- calculate u and v in camera frames, based on estimated feature position
 | 
			
		||||
				- input results into jakobi d(measurement)/d(camera 0/1)
 | 
			
		||||
				- input results into jakobi d(camera 0/1)/d(state) and jakobi d(camera 0/1)/d(feature position)
 | 
			
		||||
				- project both jakobis to nullspace of feature position jakobi
 | 
			
		||||
				- calculate residual: measurement - u and v of camera frames
 | 
			
		||||
				- project residual onto nullspace of feature position jakobi
 | 
			
		||||
 | 
			
		||||
			- stack residual and jakobians
 | 
			
		||||
 | 
			
		||||
		gating Test()
 | 
			
		||||
		
 | 
			
		||||
		*measurementUpdate()
 | 
			
		||||
			_use calculated residuals and jakobians to calculate change in error_
 | 
			
		||||
measurementUpdate():
 | 
			
		||||
	- QR reduce the stacked Measurment Jakobis
 | 
			
		||||
	- calcualte Kalman Gain based on Measurement Jakobian, Error-State Covariance and Noise
 | 
			
		||||
		_does some fancy shit here_
 | 
			
		||||
	- calculate estimated error after observation: delta_x = KalmanGain * residual 
 | 
			
		||||
	- add estimated error to state (imu states and cam states)
 | 
			
		||||
 | 
			
		||||
initialize Position ():
 | 
			
		||||
	* create initial guess for global feature position ()
 | 
			
		||||
		_uses first feature measurement on left camera and last feature measurement of right camera_
 | 
			
		||||
		- transform first measurement to plane of last measurement
 | 
			
		||||
		- calcualte least square point between rays
 | 
			
		||||
	* get position approximation using measured feature positions
 | 
			
		||||
		_using Levenberg Marqhart iterative search_
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
add Feature Observations()
 | 
			
		||||
	* if feature not in map, add feature to map
 | 
			
		||||
		_and add u0, v0, u1, v1 as first observation
 | 
			
		||||
	* if feature in map, add new observation u0,v0,u1,v1
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
state Augmentation()
 | 
			
		||||
	* Add estimated cam position to state
 | 
			
		||||
	* Update P with Jakobian of cam Position 
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
propagate IMU state ()
 | 
			
		||||
	_uses IMU process model for every saved IMU state_
 | 
			
		||||
	
 | 
			
		||||
	for every buffered imu state:
 | 
			
		||||
		
 | 
			
		||||
		*remove bias
 | 
			
		||||
		
 | 
			
		||||
		*Compute F and G matrix (continuous transition and noise cov.)
 | 
			
		||||
			_using current orientation, gyro and acc. reading_
 | 
			
		||||
		* approximate phi: phi = 1 + Fdt + ...
 | 
			
		||||
 | 
			
		||||
		* calculate new state propagating through runge kutta
 | 
			
		||||
		* modify transition matrix to have a propper null space?
 | 
			
		||||
 | 
			
		||||
		* calculate Q = Phi*G*Q_noise*GT*PhiT
 | 
			
		||||
		* calculate P = Phi*P*PhiT + Q
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
	stateAugmentation ()
 | 
			
		||||
		_save current IMU state as camera position_
 | 
			
		||||
							
								
								
									
										160
									
								
								src/image_handler.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										160
									
								
								src/image_handler.cpp
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,160 @@
 | 
			
		||||
#include <iostream>
 | 
			
		||||
#include <algorithm>
 | 
			
		||||
#include <set>
 | 
			
		||||
#include <Eigen/Dense>
 | 
			
		||||
 | 
			
		||||
#include <sensor_msgs/image_encodings.h>
 | 
			
		||||
#include <random_numbers/random_numbers.h>
 | 
			
		||||
 | 
			
		||||
#include <msckf_vio/CameraMeasurement.h>
 | 
			
		||||
#include <msckf_vio/TrackingInfo.h>
 | 
			
		||||
#include <msckf_vio/image_processor.h>
 | 
			
		||||
 | 
			
		||||
namespace msckf_vio {
 | 
			
		||||
namespace image_handler {
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
void undistortPoint(
 | 
			
		||||
    const cv::Point2f& pt_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs,
 | 
			
		||||
    cv::Point2f& pt_out,
 | 
			
		||||
    const cv::Matx33d &rectification_matrix,
 | 
			
		||||
    const cv::Vec4d &new_intrinsics) {
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
  std::vector<cv::Point2f> pts_in;
 | 
			
		||||
  std::vector<cv::Point2f> pts_out;
 | 
			
		||||
  pts_in.push_back(pt_in);
 | 
			
		||||
  if (pts_in.size() == 0) return;
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K(
 | 
			
		||||
      intrinsics[0], 0.0, intrinsics[2],
 | 
			
		||||
      0.0, intrinsics[1], intrinsics[3],
 | 
			
		||||
      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K_new(
 | 
			
		||||
      new_intrinsics[0], 0.0, new_intrinsics[2],
 | 
			
		||||
      0.0, new_intrinsics[1], new_intrinsics[3],
 | 
			
		||||
      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  if (distortion_model == "radtan") {
 | 
			
		||||
    cv::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                        rectification_matrix, K_new);
 | 
			
		||||
  } else if (distortion_model == "equidistant") {
 | 
			
		||||
    cv::fisheye::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                                 rectification_matrix, K_new);
 | 
			
		||||
  } else {
 | 
			
		||||
    ROS_WARN_ONCE("The model %s is unrecognized, use radtan instead...",
 | 
			
		||||
                  distortion_model.c_str());
 | 
			
		||||
    cv::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                        rectification_matrix, K_new);
 | 
			
		||||
  }
 | 
			
		||||
  pt_out = pts_out[0];
 | 
			
		||||
  return;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void undistortPoints(
 | 
			
		||||
    const std::vector<cv::Point2f>& pts_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs,
 | 
			
		||||
    std::vector<cv::Point2f>& pts_out,
 | 
			
		||||
    const cv::Matx33d &rectification_matrix,
 | 
			
		||||
    const cv::Vec4d &new_intrinsics) {
 | 
			
		||||
 | 
			
		||||
  if (pts_in.size() == 0) return;
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K(
 | 
			
		||||
      intrinsics[0], 0.0, intrinsics[2],
 | 
			
		||||
      0.0, intrinsics[1], intrinsics[3],
 | 
			
		||||
      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K_new(
 | 
			
		||||
      new_intrinsics[0], 0.0, new_intrinsics[2],
 | 
			
		||||
      0.0, new_intrinsics[1], new_intrinsics[3],
 | 
			
		||||
      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  if (distortion_model == "radtan") {
 | 
			
		||||
    cv::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                        rectification_matrix, K_new);
 | 
			
		||||
  } else if (distortion_model == "equidistant") {
 | 
			
		||||
    cv::fisheye::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                                 rectification_matrix, K_new);
 | 
			
		||||
  } else {
 | 
			
		||||
    ROS_WARN_ONCE("The model %s is unrecognized, use radtan instead...",
 | 
			
		||||
                  distortion_model.c_str());
 | 
			
		||||
    cv::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                        rectification_matrix, K_new);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  return;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
std::vector<cv::Point2f> distortPoints(
 | 
			
		||||
    const std::vector<cv::Point2f>& pts_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs) {
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K(intrinsics[0], 0.0, intrinsics[2],
 | 
			
		||||
                      0.0, intrinsics[1], intrinsics[3],
 | 
			
		||||
                      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  std::vector<cv::Point2f> pts_out;
 | 
			
		||||
  if (distortion_model == "radtan") {
 | 
			
		||||
    std::vector<cv::Point3f> homogenous_pts;
 | 
			
		||||
    cv::convertPointsToHomogeneous(pts_in, homogenous_pts);
 | 
			
		||||
    cv::projectPoints(homogenous_pts, cv::Vec3d::zeros(), cv::Vec3d::zeros(), K,
 | 
			
		||||
                      distortion_coeffs, pts_out);
 | 
			
		||||
  } else if (distortion_model == "equidistant") {
 | 
			
		||||
    cv::fisheye::distortPoints(pts_in, pts_out, K, distortion_coeffs);
 | 
			
		||||
  } else {
 | 
			
		||||
    ROS_WARN_ONCE("The model %s is unrecognized, using radtan instead...",
 | 
			
		||||
                  distortion_model.c_str());
 | 
			
		||||
    std::vector<cv::Point3f> homogenous_pts;
 | 
			
		||||
    cv::convertPointsToHomogeneous(pts_in, homogenous_pts);
 | 
			
		||||
    cv::projectPoints(homogenous_pts, cv::Vec3d::zeros(), cv::Vec3d::zeros(), K,
 | 
			
		||||
                      distortion_coeffs, pts_out);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  return pts_out;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
cv::Point2f distortPoint(
 | 
			
		||||
    const cv::Point2f& pt_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const std::string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs) {
 | 
			
		||||
 | 
			
		||||
  std::vector<cv::Point2f> pts_in;
 | 
			
		||||
  pts_in.push_back(pt_in);
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K(intrinsics[0], 0.0, intrinsics[2],
 | 
			
		||||
                      0.0, intrinsics[1], intrinsics[3],
 | 
			
		||||
                      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  std::vector<cv::Point2f> pts_out;
 | 
			
		||||
  if (distortion_model == "radtan") {
 | 
			
		||||
    std::vector<cv::Point3f> homogenous_pts;
 | 
			
		||||
    cv::convertPointsToHomogeneous(pts_in, homogenous_pts);
 | 
			
		||||
    cv::projectPoints(homogenous_pts, cv::Vec3d::zeros(), cv::Vec3d::zeros(), K,
 | 
			
		||||
                      distortion_coeffs, pts_out);
 | 
			
		||||
  } else if (distortion_model == "equidistant") {
 | 
			
		||||
    cv::fisheye::distortPoints(pts_in, pts_out, K, distortion_coeffs);
 | 
			
		||||
  } else {
 | 
			
		||||
    ROS_WARN_ONCE("The model %s is unrecognized, using radtan instead...",
 | 
			
		||||
                  distortion_model.c_str());
 | 
			
		||||
    std::vector<cv::Point3f> homogenous_pts;
 | 
			
		||||
    cv::convertPointsToHomogeneous(pts_in, homogenous_pts);
 | 
			
		||||
    cv::projectPoints(homogenous_pts, cv::Vec3d::zeros(), cv::Vec3d::zeros(), K,
 | 
			
		||||
                      distortion_coeffs, pts_out);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  return pts_out[0];
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
	} // namespace image_handler
 | 
			
		||||
} // namespace msckf_vio
 | 
			
		||||
@@ -17,6 +17,7 @@
 | 
			
		||||
#include <msckf_vio/TrackingInfo.h>
 | 
			
		||||
#include <msckf_vio/image_processor.h>
 | 
			
		||||
#include <msckf_vio/utils.h>
 | 
			
		||||
#include <msckf_vio/image_handler.h>
 | 
			
		||||
 | 
			
		||||
using namespace std;
 | 
			
		||||
using namespace cv;
 | 
			
		||||
@@ -43,49 +44,49 @@ ImageProcessor::~ImageProcessor() {
 | 
			
		||||
bool ImageProcessor::loadParameters() {
 | 
			
		||||
  // Camera calibration parameters
 | 
			
		||||
  nh.param<string>("cam0/distortion_model",
 | 
			
		||||
      cam0_distortion_model, string("radtan"));
 | 
			
		||||
      cam0.distortion_model, string("radtan"));
 | 
			
		||||
  nh.param<string>("cam1/distortion_model",
 | 
			
		||||
      cam1_distortion_model, string("radtan"));
 | 
			
		||||
      cam1.distortion_model, string("radtan"));
 | 
			
		||||
 | 
			
		||||
  vector<int> cam0_resolution_temp(2);
 | 
			
		||||
  nh.getParam("cam0/resolution", cam0_resolution_temp);
 | 
			
		||||
  cam0_resolution[0] = cam0_resolution_temp[0];
 | 
			
		||||
  cam0_resolution[1] = cam0_resolution_temp[1];
 | 
			
		||||
  cam0.resolution[0] = cam0_resolution_temp[0];
 | 
			
		||||
  cam0.resolution[1] = cam0_resolution_temp[1];
 | 
			
		||||
 | 
			
		||||
  vector<int> cam1_resolution_temp(2);
 | 
			
		||||
  nh.getParam("cam1/resolution", cam1_resolution_temp);
 | 
			
		||||
  cam1_resolution[0] = cam1_resolution_temp[0];
 | 
			
		||||
  cam1_resolution[1] = cam1_resolution_temp[1];
 | 
			
		||||
  cam1.resolution[0] = cam1_resolution_temp[0];
 | 
			
		||||
  cam1.resolution[1] = cam1_resolution_temp[1];
 | 
			
		||||
 | 
			
		||||
  vector<double> cam0_intrinsics_temp(4);
 | 
			
		||||
  nh.getParam("cam0/intrinsics", cam0_intrinsics_temp);
 | 
			
		||||
  cam0_intrinsics[0] = cam0_intrinsics_temp[0];
 | 
			
		||||
  cam0_intrinsics[1] = cam0_intrinsics_temp[1];
 | 
			
		||||
  cam0_intrinsics[2] = cam0_intrinsics_temp[2];
 | 
			
		||||
  cam0_intrinsics[3] = cam0_intrinsics_temp[3];
 | 
			
		||||
  cam0.intrinsics[0] = cam0_intrinsics_temp[0];
 | 
			
		||||
  cam0.intrinsics[1] = cam0_intrinsics_temp[1];
 | 
			
		||||
  cam0.intrinsics[2] = cam0_intrinsics_temp[2];
 | 
			
		||||
  cam0.intrinsics[3] = cam0_intrinsics_temp[3];
 | 
			
		||||
 | 
			
		||||
  vector<double> cam1_intrinsics_temp(4);
 | 
			
		||||
  nh.getParam("cam1/intrinsics", cam1_intrinsics_temp);
 | 
			
		||||
  cam1_intrinsics[0] = cam1_intrinsics_temp[0];
 | 
			
		||||
  cam1_intrinsics[1] = cam1_intrinsics_temp[1];
 | 
			
		||||
  cam1_intrinsics[2] = cam1_intrinsics_temp[2];
 | 
			
		||||
  cam1_intrinsics[3] = cam1_intrinsics_temp[3];
 | 
			
		||||
  cam1.intrinsics[0] = cam1_intrinsics_temp[0];
 | 
			
		||||
  cam1.intrinsics[1] = cam1_intrinsics_temp[1];
 | 
			
		||||
  cam1.intrinsics[2] = cam1_intrinsics_temp[2];
 | 
			
		||||
  cam1.intrinsics[3] = cam1_intrinsics_temp[3];
 | 
			
		||||
 | 
			
		||||
  vector<double> cam0_distortion_coeffs_temp(4);
 | 
			
		||||
  nh.getParam("cam0/distortion_coeffs",
 | 
			
		||||
      cam0_distortion_coeffs_temp);
 | 
			
		||||
  cam0_distortion_coeffs[0] = cam0_distortion_coeffs_temp[0];
 | 
			
		||||
  cam0_distortion_coeffs[1] = cam0_distortion_coeffs_temp[1];
 | 
			
		||||
  cam0_distortion_coeffs[2] = cam0_distortion_coeffs_temp[2];
 | 
			
		||||
  cam0_distortion_coeffs[3] = cam0_distortion_coeffs_temp[3];
 | 
			
		||||
  cam0.distortion_coeffs[0] = cam0_distortion_coeffs_temp[0];
 | 
			
		||||
  cam0.distortion_coeffs[1] = cam0_distortion_coeffs_temp[1];
 | 
			
		||||
  cam0.distortion_coeffs[2] = cam0_distortion_coeffs_temp[2];
 | 
			
		||||
  cam0.distortion_coeffs[3] = cam0_distortion_coeffs_temp[3];
 | 
			
		||||
 | 
			
		||||
  vector<double> cam1_distortion_coeffs_temp(4);
 | 
			
		||||
  nh.getParam("cam1/distortion_coeffs",
 | 
			
		||||
      cam1_distortion_coeffs_temp);
 | 
			
		||||
  cam1_distortion_coeffs[0] = cam1_distortion_coeffs_temp[0];
 | 
			
		||||
  cam1_distortion_coeffs[1] = cam1_distortion_coeffs_temp[1];
 | 
			
		||||
  cam1_distortion_coeffs[2] = cam1_distortion_coeffs_temp[2];
 | 
			
		||||
  cam1_distortion_coeffs[3] = cam1_distortion_coeffs_temp[3];
 | 
			
		||||
  cam1.distortion_coeffs[0] = cam1_distortion_coeffs_temp[0];
 | 
			
		||||
  cam1.distortion_coeffs[1] = cam1_distortion_coeffs_temp[1];
 | 
			
		||||
  cam1.distortion_coeffs[2] = cam1_distortion_coeffs_temp[2];
 | 
			
		||||
  cam1.distortion_coeffs[3] = cam1_distortion_coeffs_temp[3];
 | 
			
		||||
 | 
			
		||||
  cv::Mat     T_imu_cam0 = utils::getTransformCV(nh, "cam0/T_cam_imu");
 | 
			
		||||
  cv::Matx33d R_imu_cam0(T_imu_cam0(cv::Rect(0,0,3,3)));
 | 
			
		||||
@@ -123,27 +124,27 @@ bool ImageProcessor::loadParameters() {
 | 
			
		||||
      processor_config.stereo_threshold, 3);
 | 
			
		||||
 | 
			
		||||
  ROS_INFO("===========================================");
 | 
			
		||||
  ROS_INFO("cam0_resolution: %d, %d",
 | 
			
		||||
      cam0_resolution[0], cam0_resolution[1]);
 | 
			
		||||
  ROS_INFO("cam0.resolution: %d, %d",
 | 
			
		||||
      cam0.resolution[0], cam0.resolution[1]);
 | 
			
		||||
  ROS_INFO("cam0_intrinscs: %f, %f, %f, %f",
 | 
			
		||||
      cam0_intrinsics[0], cam0_intrinsics[1],
 | 
			
		||||
      cam0_intrinsics[2], cam0_intrinsics[3]);
 | 
			
		||||
  ROS_INFO("cam0_distortion_model: %s",
 | 
			
		||||
      cam0_distortion_model.c_str());
 | 
			
		||||
      cam0.intrinsics[0], cam0.intrinsics[1],
 | 
			
		||||
      cam0.intrinsics[2], cam0.intrinsics[3]);
 | 
			
		||||
  ROS_INFO("cam0.distortion_model: %s",
 | 
			
		||||
      cam0.distortion_model.c_str());
 | 
			
		||||
  ROS_INFO("cam0_distortion_coefficients: %f, %f, %f, %f",
 | 
			
		||||
      cam0_distortion_coeffs[0], cam0_distortion_coeffs[1],
 | 
			
		||||
      cam0_distortion_coeffs[2], cam0_distortion_coeffs[3]);
 | 
			
		||||
      cam0.distortion_coeffs[0], cam0.distortion_coeffs[1],
 | 
			
		||||
      cam0.distortion_coeffs[2], cam0.distortion_coeffs[3]);
 | 
			
		||||
 | 
			
		||||
  ROS_INFO("cam1_resolution: %d, %d",
 | 
			
		||||
      cam1_resolution[0], cam1_resolution[1]);
 | 
			
		||||
  ROS_INFO("cam1.resolution: %d, %d",
 | 
			
		||||
      cam1.resolution[0], cam1.resolution[1]);
 | 
			
		||||
  ROS_INFO("cam1_intrinscs: %f, %f, %f, %f",
 | 
			
		||||
      cam1_intrinsics[0], cam1_intrinsics[1],
 | 
			
		||||
      cam1_intrinsics[2], cam1_intrinsics[3]);
 | 
			
		||||
  ROS_INFO("cam1_distortion_model: %s",
 | 
			
		||||
      cam1_distortion_model.c_str());
 | 
			
		||||
      cam1.intrinsics[0], cam1.intrinsics[1],
 | 
			
		||||
      cam1.intrinsics[2], cam1.intrinsics[3]);
 | 
			
		||||
  ROS_INFO("cam1.distortion_model: %s",
 | 
			
		||||
      cam1.distortion_model.c_str());
 | 
			
		||||
  ROS_INFO("cam1_distortion_coefficients: %f, %f, %f, %f",
 | 
			
		||||
      cam1_distortion_coeffs[0], cam1_distortion_coeffs[1],
 | 
			
		||||
      cam1_distortion_coeffs[2], cam1_distortion_coeffs[3]);
 | 
			
		||||
      cam1.distortion_coeffs[0], cam1.distortion_coeffs[1],
 | 
			
		||||
      cam1.distortion_coeffs[2], cam1.distortion_coeffs[3]);
 | 
			
		||||
 | 
			
		||||
  cout << R_imu_cam0 << endl;
 | 
			
		||||
  cout << t_imu_cam0.t() << endl;
 | 
			
		||||
@@ -170,10 +171,6 @@ bool ImageProcessor::loadParameters() {
 | 
			
		||||
      processor_config.ransac_threshold);
 | 
			
		||||
  ROS_INFO("stereo_threshold: %f",
 | 
			
		||||
      processor_config.stereo_threshold);
 | 
			
		||||
  ROS_INFO("OpenCV Major Version: %d",
 | 
			
		||||
    CV_MAJOR_VERSION);
 | 
			
		||||
  ROS_INFO("OpenCV Minor Version: %d",
 | 
			
		||||
    CV_MINOR_VERSION);
 | 
			
		||||
  ROS_INFO("===========================================");
 | 
			
		||||
  return true;
 | 
			
		||||
}
 | 
			
		||||
@@ -204,13 +201,6 @@ bool ImageProcessor::initialize() {
 | 
			
		||||
  detector_ptr = FastFeatureDetector::create(
 | 
			
		||||
      processor_config.fast_threshold);
 | 
			
		||||
 | 
			
		||||
  //create gpu optical flow lk
 | 
			
		||||
  d_pyrLK_sparse = cuda::SparsePyrLKOpticalFlow::create(
 | 
			
		||||
          Size(processor_config.patch_size, processor_config.patch_size),
 | 
			
		||||
          processor_config.pyramid_levels, 
 | 
			
		||||
          processor_config.max_iteration,
 | 
			
		||||
          true);
 | 
			
		||||
 | 
			
		||||
  if (!createRosIO()) return false;
 | 
			
		||||
  ROS_INFO("Finish creating ROS IO...");
 | 
			
		||||
 | 
			
		||||
@@ -230,9 +220,7 @@ void ImageProcessor::stereoCallback(
 | 
			
		||||
      sensor_msgs::image_encodings::MONO8);
 | 
			
		||||
 | 
			
		||||
  // Build the image pyramids once since they're used at multiple places
 | 
			
		||||
 | 
			
		||||
  // removed due to alternate cuda construct
 | 
			
		||||
  //createImagePyramids();
 | 
			
		||||
  createImagePyramids();
 | 
			
		||||
 | 
			
		||||
  // Detect features in the first frame.
 | 
			
		||||
  if (is_first_img) {
 | 
			
		||||
@@ -309,7 +297,6 @@ void ImageProcessor::imuCallback(
 | 
			
		||||
 | 
			
		||||
void ImageProcessor::createImagePyramids() {
 | 
			
		||||
  const Mat& curr_cam0_img = cam0_curr_img_ptr->image;
 | 
			
		||||
  // TODO: build cuda optical flow
 | 
			
		||||
  buildOpticalFlowPyramid(
 | 
			
		||||
      curr_cam0_img, curr_cam0_pyramid_,
 | 
			
		||||
      Size(processor_config.patch_size, processor_config.patch_size),
 | 
			
		||||
@@ -317,7 +304,6 @@ void ImageProcessor::createImagePyramids() {
 | 
			
		||||
      BORDER_CONSTANT, false);
 | 
			
		||||
 | 
			
		||||
  const Mat& curr_cam1_img = cam1_curr_img_ptr->image;
 | 
			
		||||
  // TODO: build cuda optical flow
 | 
			
		||||
  buildOpticalFlowPyramid(
 | 
			
		||||
      curr_cam1_img, curr_cam1_pyramid_,
 | 
			
		||||
      Size(processor_config.patch_size, processor_config.patch_size),
 | 
			
		||||
@@ -404,7 +390,6 @@ void ImageProcessor::predictFeatureTracking(
 | 
			
		||||
    const cv::Matx33f& R_p_c,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    vector<cv::Point2f>& compensated_pts) {
 | 
			
		||||
 | 
			
		||||
  // Return directly if there are no input features.
 | 
			
		||||
  if (input_pts.size() == 0) {
 | 
			
		||||
    compensated_pts.clear();
 | 
			
		||||
@@ -435,7 +420,6 @@ void ImageProcessor::trackFeatures() {
 | 
			
		||||
    cam0_curr_img_ptr->image.rows / processor_config.grid_row;
 | 
			
		||||
  static int grid_width =
 | 
			
		||||
    cam0_curr_img_ptr->image.cols / processor_config.grid_col;
 | 
			
		||||
 | 
			
		||||
  // Compute a rough relative rotation which takes a vector
 | 
			
		||||
  // from the previous frame to the current frame.
 | 
			
		||||
  Matx33f cam0_R_p_c;
 | 
			
		||||
@@ -469,10 +453,8 @@ void ImageProcessor::trackFeatures() {
 | 
			
		||||
  vector<unsigned char> track_inliers(0);
 | 
			
		||||
 | 
			
		||||
  predictFeatureTracking(prev_cam0_points,
 | 
			
		||||
      cam0_R_p_c, cam0_intrinsics, curr_cam0_points);
 | 
			
		||||
      cam0_R_p_c, cam0.intrinsics, curr_cam0_points);
 | 
			
		||||
 | 
			
		||||
  //TODO: test change to sparse
 | 
			
		||||
  /*
 | 
			
		||||
  calcOpticalFlowPyrLK(
 | 
			
		||||
      prev_cam0_pyramid_, curr_cam0_pyramid_,
 | 
			
		||||
      prev_cam0_points, curr_cam0_points,
 | 
			
		||||
@@ -483,25 +465,6 @@ void ImageProcessor::trackFeatures() {
 | 
			
		||||
        processor_config.max_iteration,
 | 
			
		||||
        processor_config.track_precision),
 | 
			
		||||
      cv::OPTFLOW_USE_INITIAL_FLOW);
 | 
			
		||||
  */
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
  cam0_curr_img = cv::cuda::GpuMat(cam0_curr_img_ptr->image);
 | 
			
		||||
  cam1_curr_img = cv::cuda::GpuMat(cam1_curr_img_ptr->image);
 | 
			
		||||
  cam0_points_gpu = cv::cuda::GpuMat(prev_cam0_points);
 | 
			
		||||
  cam1_points_gpu = cv::cuda::GpuMat(curr_cam0_points);
 | 
			
		||||
 | 
			
		||||
  cv::cuda::GpuMat inlier_markers_gpu;
 | 
			
		||||
  d_pyrLK_sparse->calc(cam0_curr_img, 
 | 
			
		||||
                       cam1_curr_img, 
 | 
			
		||||
                       cam0_points_gpu, 
 | 
			
		||||
                       cam1_points_gpu, 
 | 
			
		||||
                       inlier_markers_gpu, 
 | 
			
		||||
                       noArray());
 | 
			
		||||
 | 
			
		||||
  utils::download(cam1_points_gpu, curr_cam0_points);
 | 
			
		||||
  utils::download(inlier_markers_gpu, track_inliers);
 | 
			
		||||
 | 
			
		||||
  // Mark those tracked points out of the image region
 | 
			
		||||
  // as untracked.
 | 
			
		||||
@@ -585,14 +548,14 @@ void ImageProcessor::trackFeatures() {
 | 
			
		||||
  // Step 2 and 3: RANSAC on temporal image pairs of cam0 and cam1.
 | 
			
		||||
  vector<int> cam0_ransac_inliers(0);
 | 
			
		||||
  twoPointRansac(prev_matched_cam0_points, curr_matched_cam0_points,
 | 
			
		||||
      cam0_R_p_c, cam0_intrinsics, cam0_distortion_model,
 | 
			
		||||
      cam0_distortion_coeffs, processor_config.ransac_threshold,
 | 
			
		||||
      cam0_R_p_c, cam0.intrinsics, cam0.distortion_model,
 | 
			
		||||
      cam0.distortion_coeffs, processor_config.ransac_threshold,
 | 
			
		||||
      0.99, cam0_ransac_inliers);
 | 
			
		||||
 | 
			
		||||
  vector<int> cam1_ransac_inliers(0);
 | 
			
		||||
  twoPointRansac(prev_matched_cam1_points, curr_matched_cam1_points,
 | 
			
		||||
      cam1_R_p_c, cam1_intrinsics, cam1_distortion_model,
 | 
			
		||||
      cam1_distortion_coeffs, processor_config.ransac_threshold,
 | 
			
		||||
      cam1_R_p_c, cam1.intrinsics, cam1.distortion_model,
 | 
			
		||||
      cam1.distortion_coeffs, processor_config.ransac_threshold,
 | 
			
		||||
      0.99, cam1_ransac_inliers);
 | 
			
		||||
 | 
			
		||||
  // Number of features after ransac.
 | 
			
		||||
@@ -646,7 +609,6 @@ void ImageProcessor::stereoMatch(
 | 
			
		||||
    const vector<cv::Point2f>& cam0_points,
 | 
			
		||||
    vector<cv::Point2f>& cam1_points,
 | 
			
		||||
    vector<unsigned char>& inlier_markers) {
 | 
			
		||||
 | 
			
		||||
  if (cam0_points.size() == 0) return;
 | 
			
		||||
 | 
			
		||||
  if(cam1_points.size() == 0) {
 | 
			
		||||
@@ -654,31 +616,15 @@ void ImageProcessor::stereoMatch(
 | 
			
		||||
    // rotation from stereo extrinsics
 | 
			
		||||
    const cv::Matx33d R_cam0_cam1 = R_cam1_imu.t() * R_cam0_imu;
 | 
			
		||||
    vector<cv::Point2f> cam0_points_undistorted;
 | 
			
		||||
    undistortPoints(cam0_points, cam0_intrinsics, cam0_distortion_model,
 | 
			
		||||
                    cam0_distortion_coeffs, cam0_points_undistorted,
 | 
			
		||||
    image_handler::undistortPoints(cam0_points, cam0.intrinsics, cam0.distortion_model,
 | 
			
		||||
                    cam0.distortion_coeffs, cam0_points_undistorted,
 | 
			
		||||
                    R_cam0_cam1);
 | 
			
		||||
    cam1_points = distortPoints(cam0_points_undistorted, cam1_intrinsics,
 | 
			
		||||
                                cam1_distortion_model, cam1_distortion_coeffs);
 | 
			
		||||
 | 
			
		||||
    cam1_points = image_handler::distortPoints(cam0_points_undistorted, cam1.intrinsics,
 | 
			
		||||
                                cam1.distortion_model, cam1.distortion_coeffs);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  cam0_curr_img = cv::cuda::GpuMat(cam0_curr_img_ptr->image);
 | 
			
		||||
  cam1_curr_img = cv::cuda::GpuMat(cam1_curr_img_ptr->image);
 | 
			
		||||
  cam0_points_gpu = cv::cuda::GpuMat(cam0_points);
 | 
			
		||||
  cam1_points_gpu = cv::cuda::GpuMat(cam1_points);
 | 
			
		||||
 | 
			
		||||
  cv::cuda::GpuMat inlier_markers_gpu;
 | 
			
		||||
  d_pyrLK_sparse->calc(cam0_curr_img, 
 | 
			
		||||
                       cam1_curr_img, 
 | 
			
		||||
                       cam0_points_gpu, 
 | 
			
		||||
                       cam1_points_gpu, 
 | 
			
		||||
                       inlier_markers_gpu, 
 | 
			
		||||
                       noArray());
 | 
			
		||||
 | 
			
		||||
  utils::download(cam1_points_gpu, cam1_points);
 | 
			
		||||
  utils::download(inlier_markers_gpu, inlier_markers);
 | 
			
		||||
 | 
			
		||||
  // Track features using LK optical flow method.
 | 
			
		||||
  /*
 | 
			
		||||
  calcOpticalFlowPyrLK(curr_cam0_pyramid_, curr_cam1_pyramid_,
 | 
			
		||||
      cam0_points, cam1_points,
 | 
			
		||||
      inlier_markers, noArray(),
 | 
			
		||||
@@ -688,7 +634,7 @@ void ImageProcessor::stereoMatch(
 | 
			
		||||
                   processor_config.max_iteration,
 | 
			
		||||
                   processor_config.track_precision),
 | 
			
		||||
      cv::OPTFLOW_USE_INITIAL_FLOW);
 | 
			
		||||
  */
 | 
			
		||||
 | 
			
		||||
  // Mark those tracked points out of the image region
 | 
			
		||||
  // as untracked.
 | 
			
		||||
  for (int i = 0; i < cam1_points.size(); ++i) {
 | 
			
		||||
@@ -715,16 +661,16 @@ void ImageProcessor::stereoMatch(
 | 
			
		||||
  // essential matrix.
 | 
			
		||||
  vector<cv::Point2f> cam0_points_undistorted(0);
 | 
			
		||||
  vector<cv::Point2f> cam1_points_undistorted(0);
 | 
			
		||||
  undistortPoints(
 | 
			
		||||
      cam0_points, cam0_intrinsics, cam0_distortion_model,
 | 
			
		||||
      cam0_distortion_coeffs, cam0_points_undistorted);
 | 
			
		||||
  undistortPoints(
 | 
			
		||||
      cam1_points, cam1_intrinsics, cam1_distortion_model,
 | 
			
		||||
      cam1_distortion_coeffs, cam1_points_undistorted);
 | 
			
		||||
  image_handler::undistortPoints(
 | 
			
		||||
      cam0_points, cam0.intrinsics, cam0.distortion_model,
 | 
			
		||||
      cam0.distortion_coeffs, cam0_points_undistorted);
 | 
			
		||||
  image_handler::undistortPoints(
 | 
			
		||||
      cam1_points, cam1.intrinsics, cam1.distortion_model,
 | 
			
		||||
      cam1.distortion_coeffs, cam1_points_undistorted);
 | 
			
		||||
 | 
			
		||||
  double norm_pixel_unit = 4.0 / (
 | 
			
		||||
      cam0_intrinsics[0]+cam0_intrinsics[1]+
 | 
			
		||||
      cam1_intrinsics[0]+cam1_intrinsics[1]);
 | 
			
		||||
      cam0.intrinsics[0]+cam0.intrinsics[1]+
 | 
			
		||||
      cam1.intrinsics[0]+cam1.intrinsics[1]);
 | 
			
		||||
 | 
			
		||||
  for (int i = 0; i < cam0_points_undistorted.size(); ++i) {
 | 
			
		||||
    if (inlier_markers[i] == 0) continue;
 | 
			
		||||
@@ -751,8 +697,8 @@ void ImageProcessor::addNewFeatures() {
 | 
			
		||||
    cam0_curr_img_ptr->image.rows / processor_config.grid_row;
 | 
			
		||||
  static int grid_width =
 | 
			
		||||
    cam0_curr_img_ptr->image.cols / processor_config.grid_col;
 | 
			
		||||
 | 
			
		||||
  // Create a mask to avoid redetecting existing features.
 | 
			
		||||
 | 
			
		||||
  Mat mask(curr_img.rows, curr_img.cols, CV_8U, Scalar(1));
 | 
			
		||||
 | 
			
		||||
  for (const auto& features : *curr_features_ptr) {
 | 
			
		||||
@@ -772,7 +718,6 @@ void ImageProcessor::addNewFeatures() {
 | 
			
		||||
      mask(row_range, col_range) = 0;
 | 
			
		||||
    }
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  // Detect new features.
 | 
			
		||||
  vector<KeyPoint> new_features(0);
 | 
			
		||||
  detector_ptr->detect(curr_img, new_features, mask);
 | 
			
		||||
@@ -787,7 +732,6 @@ void ImageProcessor::addNewFeatures() {
 | 
			
		||||
    new_feature_sieve[
 | 
			
		||||
      row*processor_config.grid_col+col].push_back(feature);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  new_features.clear();
 | 
			
		||||
  for (auto& item : new_feature_sieve) {
 | 
			
		||||
    if (item.size() > processor_config.grid_max_feature_num) {
 | 
			
		||||
@@ -800,7 +744,6 @@ void ImageProcessor::addNewFeatures() {
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  int detected_new_features = new_features.size();
 | 
			
		||||
 | 
			
		||||
  // Find the stereo matched points for the newly
 | 
			
		||||
  // detected features.
 | 
			
		||||
  vector<cv::Point2f> cam0_points(new_features.size());
 | 
			
		||||
@@ -828,7 +771,6 @@ void ImageProcessor::addNewFeatures() {
 | 
			
		||||
      static_cast<double>(detected_new_features) < 0.1)
 | 
			
		||||
    ROS_WARN("Images at [%f] seems unsynced...",
 | 
			
		||||
        cam0_curr_img_ptr->header.stamp.toSec());
 | 
			
		||||
 | 
			
		||||
  // Group the features into grids
 | 
			
		||||
  GridFeatures grid_new_features;
 | 
			
		||||
  for (int code = 0; code <
 | 
			
		||||
@@ -850,7 +792,6 @@ void ImageProcessor::addNewFeatures() {
 | 
			
		||||
    new_feature.cam1_point = cam1_point;
 | 
			
		||||
    grid_new_features[code].push_back(new_feature);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  // Sort the new features in each grid based on its response.
 | 
			
		||||
  for (auto& item : grid_new_features)
 | 
			
		||||
    std::sort(item.second.begin(), item.second.end(),
 | 
			
		||||
@@ -900,73 +841,6 @@ void ImageProcessor::pruneGridFeatures() {
 | 
			
		||||
  return;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void ImageProcessor::undistortPoints(
 | 
			
		||||
    const vector<cv::Point2f>& pts_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs,
 | 
			
		||||
    vector<cv::Point2f>& pts_out,
 | 
			
		||||
    const cv::Matx33d &rectification_matrix,
 | 
			
		||||
    const cv::Vec4d &new_intrinsics) {
 | 
			
		||||
 | 
			
		||||
  if (pts_in.size() == 0) return;
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K(
 | 
			
		||||
      intrinsics[0], 0.0, intrinsics[2],
 | 
			
		||||
      0.0, intrinsics[1], intrinsics[3],
 | 
			
		||||
      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K_new(
 | 
			
		||||
      new_intrinsics[0], 0.0, new_intrinsics[2],
 | 
			
		||||
      0.0, new_intrinsics[1], new_intrinsics[3],
 | 
			
		||||
      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  if (distortion_model == "radtan") {
 | 
			
		||||
    cv::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                        rectification_matrix, K_new);
 | 
			
		||||
  } else if (distortion_model == "equidistant") {
 | 
			
		||||
    cv::fisheye::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                                 rectification_matrix, K_new);
 | 
			
		||||
  } else {
 | 
			
		||||
    ROS_WARN_ONCE("The model %s is unrecognized, use radtan instead...",
 | 
			
		||||
                  distortion_model.c_str());
 | 
			
		||||
    cv::undistortPoints(pts_in, pts_out, K, distortion_coeffs,
 | 
			
		||||
                        rectification_matrix, K_new);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  return;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
vector<cv::Point2f> ImageProcessor::distortPoints(
 | 
			
		||||
    const vector<cv::Point2f>& pts_in,
 | 
			
		||||
    const cv::Vec4d& intrinsics,
 | 
			
		||||
    const string& distortion_model,
 | 
			
		||||
    const cv::Vec4d& distortion_coeffs) {
 | 
			
		||||
 | 
			
		||||
  const cv::Matx33d K(intrinsics[0], 0.0, intrinsics[2],
 | 
			
		||||
                      0.0, intrinsics[1], intrinsics[3],
 | 
			
		||||
                      0.0, 0.0, 1.0);
 | 
			
		||||
 | 
			
		||||
  vector<cv::Point2f> pts_out;
 | 
			
		||||
  if (distortion_model == "radtan") {
 | 
			
		||||
    vector<cv::Point3f> homogenous_pts;
 | 
			
		||||
    cv::convertPointsToHomogeneous(pts_in, homogenous_pts);
 | 
			
		||||
    cv::projectPoints(homogenous_pts, cv::Vec3d::zeros(), cv::Vec3d::zeros(), K,
 | 
			
		||||
                      distortion_coeffs, pts_out);
 | 
			
		||||
  } else if (distortion_model == "equidistant") {
 | 
			
		||||
    cv::fisheye::distortPoints(pts_in, pts_out, K, distortion_coeffs);
 | 
			
		||||
  } else {
 | 
			
		||||
    ROS_WARN_ONCE("The model %s is unrecognized, using radtan instead...",
 | 
			
		||||
                  distortion_model.c_str());
 | 
			
		||||
    vector<cv::Point3f> homogenous_pts;
 | 
			
		||||
    cv::convertPointsToHomogeneous(pts_in, homogenous_pts);
 | 
			
		||||
    cv::projectPoints(homogenous_pts, cv::Vec3d::zeros(), cv::Vec3d::zeros(), K,
 | 
			
		||||
                      distortion_coeffs, pts_out);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  return pts_out;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void ImageProcessor::integrateImuData(
 | 
			
		||||
    Matx33f& cam0_R_p_c, Matx33f& cam1_R_p_c) {
 | 
			
		||||
  // Find the start and the end limit within the imu msg buffer.
 | 
			
		||||
@@ -1018,7 +892,6 @@ void ImageProcessor::integrateImuData(
 | 
			
		||||
void ImageProcessor::rescalePoints(
 | 
			
		||||
    vector<Point2f>& pts1, vector<Point2f>& pts2,
 | 
			
		||||
    float& scaling_factor) {
 | 
			
		||||
 | 
			
		||||
  scaling_factor = 0.0f;
 | 
			
		||||
 | 
			
		||||
  for (int i = 0; i < pts1.size(); ++i) {
 | 
			
		||||
@@ -1048,7 +921,7 @@ void ImageProcessor::twoPointRansac(
 | 
			
		||||
 | 
			
		||||
  // Check the size of input point size.
 | 
			
		||||
  if (pts1.size() != pts2.size())
 | 
			
		||||
    ROS_ERROR("Sets of different size (%i and %i) are used...",
 | 
			
		||||
    ROS_ERROR("Sets of different size (%lu and %lu) are used...",
 | 
			
		||||
        pts1.size(), pts2.size());
 | 
			
		||||
 | 
			
		||||
  double norm_pixel_unit = 2.0 / (intrinsics[0]+intrinsics[1]);
 | 
			
		||||
@@ -1062,10 +935,10 @@ void ImageProcessor::twoPointRansac(
 | 
			
		||||
  // Undistort all the points.
 | 
			
		||||
  vector<Point2f> pts1_undistorted(pts1.size());
 | 
			
		||||
  vector<Point2f> pts2_undistorted(pts2.size());
 | 
			
		||||
  undistortPoints(
 | 
			
		||||
  image_handler::undistortPoints(
 | 
			
		||||
      pts1, intrinsics, distortion_model,
 | 
			
		||||
      distortion_coeffs, pts1_undistorted);
 | 
			
		||||
  undistortPoints(
 | 
			
		||||
  image_handler::undistortPoints(
 | 
			
		||||
      pts2, intrinsics, distortion_model,
 | 
			
		||||
      distortion_coeffs, pts2_undistorted);
 | 
			
		||||
 | 
			
		||||
@@ -1283,7 +1156,6 @@ void ImageProcessor::twoPointRansac(
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void ImageProcessor::publish() {
 | 
			
		||||
 | 
			
		||||
  // Publish features.
 | 
			
		||||
  CameraMeasurementPtr feature_msg_ptr(new CameraMeasurement);
 | 
			
		||||
  feature_msg_ptr->header.stamp = cam0_curr_img_ptr->header.stamp;
 | 
			
		||||
@@ -1303,12 +1175,12 @@ void ImageProcessor::publish() {
 | 
			
		||||
  vector<Point2f> curr_cam0_points_undistorted(0);
 | 
			
		||||
  vector<Point2f> curr_cam1_points_undistorted(0);
 | 
			
		||||
 | 
			
		||||
  undistortPoints(
 | 
			
		||||
      curr_cam0_points, cam0_intrinsics, cam0_distortion_model,
 | 
			
		||||
      cam0_distortion_coeffs, curr_cam0_points_undistorted);
 | 
			
		||||
  undistortPoints(
 | 
			
		||||
      curr_cam1_points, cam1_intrinsics, cam1_distortion_model,
 | 
			
		||||
      cam1_distortion_coeffs, curr_cam1_points_undistorted);
 | 
			
		||||
  image_handler::undistortPoints(
 | 
			
		||||
      curr_cam0_points, cam0.intrinsics, cam0.distortion_model,
 | 
			
		||||
      cam0.distortion_coeffs, curr_cam0_points_undistorted);
 | 
			
		||||
  image_handler::undistortPoints(
 | 
			
		||||
      curr_cam1_points, cam1.intrinsics, cam1.distortion_model,
 | 
			
		||||
      cam1.distortion_coeffs, curr_cam1_points_undistorted);
 | 
			
		||||
 | 
			
		||||
  for (int i = 0; i < curr_ids.size(); ++i) {
 | 
			
		||||
    feature_msg_ptr->features.push_back(FeatureMeasurement());
 | 
			
		||||
 
 | 
			
		||||
							
								
								
									
										1128
									
								
								src/msckf_vio.cpp
									
									
									
									
									
								
							
							
						
						
									
										1128
									
								
								src/msckf_vio.cpp
									
									
									
									
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							@@ -11,20 +11,6 @@
 | 
			
		||||
namespace msckf_vio {
 | 
			
		||||
namespace utils {
 | 
			
		||||
 | 
			
		||||
void download(const cv::cuda::GpuMat& d_mat, std::vector<cv::Point2f>& vec)
 | 
			
		||||
{
 | 
			
		||||
    vec.resize(d_mat.cols);
 | 
			
		||||
    cv::Mat mat(1, d_mat.cols, CV_32FC2, (void*)&vec[0]);
 | 
			
		||||
    d_mat.download(mat);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void download(const cv::cuda::GpuMat& d_mat, std::vector<uchar>& vec)
 | 
			
		||||
{
 | 
			
		||||
    vec.resize(d_mat.cols);
 | 
			
		||||
    cv::Mat mat(1, d_mat.cols, CV_8UC1, (void*)&vec[0]);
 | 
			
		||||
    d_mat.download(mat);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
 | 
			
		||||
                                    const std::string &field) {
 | 
			
		||||
  Eigen::Isometry3d T;
 | 
			
		||||
 
 | 
			
		||||
		Reference in New Issue
	
	Block a user