Compare commits
1 Commits
photometry
...
LKcuda
Author | SHA1 | Date | |
---|---|---|---|
c6b8a2c2fc |
@ -24,7 +24,6 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
pcl_conversions
|
pcl_conversions
|
||||||
pcl_ros
|
pcl_ros
|
||||||
std_srvs
|
std_srvs
|
||||||
visualization_msgs
|
|
||||||
)
|
)
|
||||||
|
|
||||||
## System dependencies are found with CMake's conventions
|
## System dependencies are found with CMake's conventions
|
||||||
@ -80,7 +79,6 @@ include_directories(
|
|||||||
add_library(msckf_vio
|
add_library(msckf_vio
|
||||||
src/msckf_vio.cpp
|
src/msckf_vio.cpp
|
||||||
src/utils.cpp
|
src/utils.cpp
|
||||||
src/image_handler.cpp
|
|
||||||
)
|
)
|
||||||
add_dependencies(msckf_vio
|
add_dependencies(msckf_vio
|
||||||
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
||||||
@ -89,7 +87,6 @@ add_dependencies(msckf_vio
|
|||||||
target_link_libraries(msckf_vio
|
target_link_libraries(msckf_vio
|
||||||
${catkin_LIBRARIES}
|
${catkin_LIBRARIES}
|
||||||
${SUITESPARSE_LIBRARIES}
|
${SUITESPARSE_LIBRARIES}
|
||||||
${OpenCV_LIBRARIES}
|
|
||||||
)
|
)
|
||||||
|
|
||||||
# Msckf Vio nodelet
|
# Msckf Vio nodelet
|
||||||
@ -109,7 +106,6 @@ target_link_libraries(msckf_vio_nodelet
|
|||||||
add_library(image_processor
|
add_library(image_processor
|
||||||
src/image_processor.cpp
|
src/image_processor.cpp
|
||||||
src/utils.cpp
|
src/utils.cpp
|
||||||
src/image_handler.cpp
|
|
||||||
)
|
)
|
||||||
add_dependencies(image_processor
|
add_dependencies(image_processor
|
||||||
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
${${PROJECT_NAME}_EXPORTED_TARGETS}
|
||||||
|
@ -1,36 +0,0 @@
|
|||||||
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,34 +15,6 @@
|
|||||||
#include "imu_state.h"
|
#include "imu_state.h"
|
||||||
|
|
||||||
namespace msckf_vio {
|
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
|
* @brief CAMState Stored camera state in order to
|
||||||
* form measurement model.
|
* form measurement model.
|
||||||
@ -63,9 +35,6 @@ struct CAMState {
|
|||||||
// Position of the camera frame in the world frame.
|
// Position of the camera frame in the world frame.
|
||||||
Eigen::Vector3d position;
|
Eigen::Vector3d position;
|
||||||
|
|
||||||
// Illumination Information of the frame
|
|
||||||
IlluminationParameter illumination;
|
|
||||||
|
|
||||||
// These two variables should have the same physical
|
// These two variables should have the same physical
|
||||||
// interpretation with `orientation` and `position`.
|
// interpretation with `orientation` and `position`.
|
||||||
// There two variables are used to modify the measurement
|
// There two variables are used to modify the measurement
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -1,50 +0,0 @@
|
|||||||
#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,6 +14,10 @@
|
|||||||
#include <opencv2/opencv.hpp>
|
#include <opencv2/opencv.hpp>
|
||||||
#include <opencv2/video.hpp>
|
#include <opencv2/video.hpp>
|
||||||
|
|
||||||
|
#include <opencv2/cudaoptflow.hpp>
|
||||||
|
#include <opencv2/cudaimgproc.hpp>
|
||||||
|
#include <opencv2/cudaarithm.hpp>
|
||||||
|
|
||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <cv_bridge/cv_bridge.h>
|
#include <cv_bridge/cv_bridge.h>
|
||||||
#include <image_transport/image_transport.h>
|
#include <image_transport/image_transport.h>
|
||||||
@ -22,8 +26,6 @@
|
|||||||
#include <message_filters/subscriber.h>
|
#include <message_filters/subscriber.h>
|
||||||
#include <message_filters/time_synchronizer.h>
|
#include <message_filters/time_synchronizer.h>
|
||||||
|
|
||||||
#include "cam_state.h"
|
|
||||||
|
|
||||||
namespace msckf_vio {
|
namespace msckf_vio {
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -310,7 +312,7 @@ private:
|
|||||||
const std::vector<unsigned char>& markers,
|
const std::vector<unsigned char>& markers,
|
||||||
std::vector<T>& refined_vec) {
|
std::vector<T>& refined_vec) {
|
||||||
if (raw_vec.size() != markers.size()) {
|
if (raw_vec.size() != markers.size()) {
|
||||||
ROS_WARN("The input size of raw_vec(%lu) and markers(%lu) does not match...",
|
ROS_WARN("The input size of raw_vec(%i) and markers(%i) does not match...",
|
||||||
raw_vec.size(), markers.size());
|
raw_vec.size(), markers.size());
|
||||||
}
|
}
|
||||||
for (int i = 0; i < markers.size(); ++i) {
|
for (int i = 0; i < markers.size(); ++i) {
|
||||||
@ -334,8 +336,15 @@ private:
|
|||||||
std::vector<sensor_msgs::Imu> imu_msg_buffer;
|
std::vector<sensor_msgs::Imu> imu_msg_buffer;
|
||||||
|
|
||||||
// Camera calibration parameters
|
// Camera calibration parameters
|
||||||
CameraCalibration cam0;
|
std::string cam0_distortion_model;
|
||||||
CameraCalibration cam1;
|
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;
|
||||||
|
|
||||||
// Take a vector from cam0 frame to the IMU frame.
|
// Take a vector from cam0 frame to the IMU frame.
|
||||||
cv::Matx33d R_cam0_imu;
|
cv::Matx33d R_cam0_imu;
|
||||||
@ -358,6 +367,13 @@ private:
|
|||||||
boost::shared_ptr<GridFeatures> prev_features_ptr;
|
boost::shared_ptr<GridFeatures> prev_features_ptr;
|
||||||
boost::shared_ptr<GridFeatures> curr_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.
|
// Number of features after each outlier removal step.
|
||||||
int before_tracking;
|
int before_tracking;
|
||||||
int after_tracking;
|
int after_tracking;
|
||||||
|
@ -43,50 +43,6 @@ inline void quaternionNormalize(Eigen::Vector4d& q) {
|
|||||||
return;
|
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
|
* @brief Perform q1 * q2
|
||||||
*/
|
*/
|
||||||
|
@ -14,17 +14,11 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
#include <Eigen/Dense>
|
#include <Eigen/Dense>
|
||||||
#include <Eigen/Geometry>
|
#include <Eigen/Geometry>
|
||||||
|
|
||||||
#include <boost/shared_ptr.hpp>
|
#include <boost/shared_ptr.hpp>
|
||||||
#include <opencv2/opencv.hpp>
|
|
||||||
#include <opencv2/video.hpp>
|
|
||||||
|
|
||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <sensor_msgs/Imu.h>
|
#include <sensor_msgs/Imu.h>
|
||||||
#include <sensor_msgs/Image.h>
|
|
||||||
#include <sensor_msgs/PointCloud.h>
|
|
||||||
#include <nav_msgs/Odometry.h>
|
#include <nav_msgs/Odometry.h>
|
||||||
#include <std_msgs/Float64.h>
|
|
||||||
#include <tf/transform_broadcaster.h>
|
#include <tf/transform_broadcaster.h>
|
||||||
#include <std_srvs/Trigger.h>
|
#include <std_srvs/Trigger.h>
|
||||||
|
|
||||||
@ -33,11 +27,6 @@
|
|||||||
#include "feature.hpp"
|
#include "feature.hpp"
|
||||||
#include <msckf_vio/CameraMeasurement.h>
|
#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 {
|
namespace msckf_vio {
|
||||||
/*
|
/*
|
||||||
* @brief MsckfVio Implements the algorithm in
|
* @brief MsckfVio Implements the algorithm in
|
||||||
@ -108,27 +97,11 @@ class MsckfVio {
|
|||||||
void imuCallback(const sensor_msgs::ImuConstPtr& msg);
|
void imuCallback(const sensor_msgs::ImuConstPtr& msg);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* @brief truthCallback
|
* @brief featureCallback
|
||||||
* Callback function for ground truth navigation information
|
* Callback function for feature measurements.
|
||||||
* @param TransformStamped msg
|
* @param msg Stereo feature measurements.
|
||||||
*/
|
*/
|
||||||
void truthCallback(
|
void featureCallback(const CameraMeasurementConstPtr& msg);
|
||||||
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 imageCallback (
|
|
||||||
const sensor_msgs::ImageConstPtr& cam0_img,
|
|
||||||
const sensor_msgs::ImageConstPtr& cam1_img,
|
|
||||||
const CameraMeasurementConstPtr& feature_msg);
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* @brief publish Publish the results of VIO.
|
* @brief publish Publish the results of VIO.
|
||||||
@ -153,26 +126,6 @@ class MsckfVio {
|
|||||||
bool resetCallback(std_srvs::Trigger::Request& req,
|
bool resetCallback(std_srvs::Trigger::Request& req,
|
||||||
std_srvs::Trigger::Response& res);
|
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
|
// Filter related functions
|
||||||
// Propogate the state
|
// Propogate the state
|
||||||
void batchImuProcessing(
|
void batchImuProcessing(
|
||||||
@ -184,39 +137,21 @@ class MsckfVio {
|
|||||||
const Eigen::Vector3d& gyro,
|
const Eigen::Vector3d& gyro,
|
||||||
const Eigen::Vector3d& acc);
|
const Eigen::Vector3d& acc);
|
||||||
|
|
||||||
// groundtruth state augmentation
|
|
||||||
void truePhotometricStateAugmentation(const double& time);
|
|
||||||
|
|
||||||
// Measurement update
|
// Measurement update
|
||||||
void stateAugmentation(const double& time);
|
void stateAugmentation(const double& time);
|
||||||
void PhotometricStateAugmentation(const double& time);
|
|
||||||
void addFeatureObservations(const CameraMeasurementConstPtr& msg);
|
void addFeatureObservations(const CameraMeasurementConstPtr& msg);
|
||||||
// This function is used to compute the measurement Jacobian
|
// This function is used to compute the measurement Jacobian
|
||||||
// for a single feature observed at a single camera frame.
|
// for a single feature observed at a single camera frame.
|
||||||
void measurementJacobian(const StateIDType& cam_state_id,
|
void measurementJacobian(const StateIDType& cam_state_id,
|
||||||
const FeatureIDType& feature_id,
|
const FeatureIDType& feature_id,
|
||||||
Eigen::Matrix<double, 2, 6>& H_x,
|
Eigen::Matrix<double, 4, 6>& H_x,
|
||||||
Eigen::Matrix<double, 2, 3>& H_f,
|
Eigen::Matrix<double, 4, 3>& H_f,
|
||||||
Eigen::Vector2d& r);
|
Eigen::Vector4d& r);
|
||||||
// This function computes the Jacobian of all measurements viewed
|
// This function computes the Jacobian of all measurements viewed
|
||||||
// in the given camera states of this feature.
|
// in the given camera states of this feature.
|
||||||
void featureJacobian(const FeatureIDType& feature_id,
|
void featureJacobian(const FeatureIDType& feature_id,
|
||||||
const std::vector<StateIDType>& cam_state_ids,
|
const std::vector<StateIDType>& cam_state_ids,
|
||||||
Eigen::MatrixXd& H_x, Eigen::VectorXd& r);
|
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,
|
void measurementUpdate(const Eigen::MatrixXd& H,
|
||||||
const Eigen::VectorXd& r);
|
const Eigen::VectorXd& r);
|
||||||
bool gatingTest(const Eigen::MatrixXd& H,
|
bool gatingTest(const Eigen::MatrixXd& H,
|
||||||
@ -228,32 +163,11 @@ class MsckfVio {
|
|||||||
// Reset the system online if the uncertainty is too large.
|
// Reset the system online if the uncertainty is too large.
|
||||||
void onlineReset();
|
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.
|
// Chi squared test table.
|
||||||
static std::map<int, double> chi_squared_test_table;
|
static std::map<int, double> chi_squared_test_table;
|
||||||
|
|
||||||
// State vector
|
// State vector
|
||||||
StateServer state_server;
|
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
|
// Maximum number of camera states
|
||||||
int max_cam_state_size;
|
int max_cam_state_size;
|
||||||
|
|
||||||
@ -265,22 +179,6 @@ class MsckfVio {
|
|||||||
// transfer delay between IMU and Image messages.
|
// transfer delay between IMU and Image messages.
|
||||||
std::vector<sensor_msgs::Imu> imu_msg_buffer;
|
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.
|
// Indicate if the gravity vector is set.
|
||||||
bool is_gravity_set;
|
bool is_gravity_set;
|
||||||
|
|
||||||
@ -308,20 +206,12 @@ class MsckfVio {
|
|||||||
|
|
||||||
// Subscribers and publishers
|
// Subscribers and publishers
|
||||||
ros::Subscriber imu_sub;
|
ros::Subscriber imu_sub;
|
||||||
ros::Subscriber truth_sub;
|
ros::Subscriber feature_sub;
|
||||||
ros::Publisher odom_pub;
|
ros::Publisher odom_pub;
|
||||||
ros::Publisher marker_pub;
|
|
||||||
ros::Publisher feature_pub;
|
ros::Publisher feature_pub;
|
||||||
tf::TransformBroadcaster tf_pub;
|
tf::TransformBroadcaster tf_pub;
|
||||||
ros::ServiceServer reset_srv;
|
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
|
// Frame id
|
||||||
std::string fixed_frame_id;
|
std::string fixed_frame_id;
|
||||||
std::string child_frame_id;
|
std::string child_frame_id;
|
||||||
@ -342,9 +232,6 @@ class MsckfVio {
|
|||||||
ros::Publisher mocap_odom_pub;
|
ros::Publisher mocap_odom_pub;
|
||||||
geometry_msgs::TransformStamped raw_mocap_odom_msg;
|
geometry_msgs::TransformStamped raw_mocap_odom_msg;
|
||||||
Eigen::Isometry3d mocap_initial_frame;
|
Eigen::Isometry3d mocap_initial_frame;
|
||||||
|
|
||||||
Eigen::Vector4d mocap_initial_orientation;
|
|
||||||
Eigen::Vector3d mocap_initial_position;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef MsckfVio::Ptr MsckfVioPtr;
|
typedef MsckfVio::Ptr MsckfVioPtr;
|
||||||
|
@ -11,6 +11,9 @@
|
|||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <opencv2/core/core.hpp>
|
#include <opencv2/core/core.hpp>
|
||||||
|
#include <opencv2/cudaoptflow.hpp>
|
||||||
|
#include <opencv2/cudaimgproc.hpp>
|
||||||
|
#include <opencv2/cudaarithm.hpp>
|
||||||
#include <Eigen/Geometry>
|
#include <Eigen/Geometry>
|
||||||
|
|
||||||
namespace msckf_vio {
|
namespace msckf_vio {
|
||||||
@ -18,6 +21,10 @@ namespace msckf_vio {
|
|||||||
* @brief utilities for msckf_vio
|
* @brief utilities for msckf_vio
|
||||||
*/
|
*/
|
||||||
namespace utils {
|
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,
|
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
|
||||||
const std::string &field);
|
const std::string &field);
|
||||||
|
|
||||||
|
@ -8,8 +8,7 @@
|
|||||||
<group ns="$(arg robot)">
|
<group ns="$(arg robot)">
|
||||||
<node pkg="nodelet" type="nodelet" name="image_processor"
|
<node pkg="nodelet" type="nodelet" name="image_processor"
|
||||||
args="standalone msckf_vio/ImageProcessorNodelet"
|
args="standalone msckf_vio/ImageProcessorNodelet"
|
||||||
output="screen"
|
output="screen">
|
||||||
>
|
|
||||||
|
|
||||||
<rosparam command="load" file="$(arg calibration_file)"/>
|
<rosparam command="load" file="$(arg calibration_file)"/>
|
||||||
<param name="grid_row" value="4"/>
|
<param name="grid_row" value="4"/>
|
||||||
|
@ -1,33 +0,0 @@
|
|||||||
<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>
|
|
@ -1,34 +0,0 @@
|
|||||||
<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>
|
|
@ -1,75 +0,0 @@
|
|||||||
<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,9 +53,6 @@
|
|||||||
<param name="initial_covariance/extrinsic_translation_cov" value="2.5e-5"/>
|
<param name="initial_covariance/extrinsic_translation_cov" value="2.5e-5"/>
|
||||||
|
|
||||||
<remap from="~imu" to="/imu0"/>
|
<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"/>
|
<remap from="~features" to="image_processor/features"/>
|
||||||
|
|
||||||
</node>
|
</node>
|
||||||
|
@ -1,61 +0,0 @@
|
|||||||
<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>
|
|
@ -1,74 +0,0 @@
|
|||||||
<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 @@
|
|||||||
Header header
|
std_msgs/Header header
|
||||||
# All features on the current image,
|
# All features on the current image,
|
||||||
# including tracked ones and newly detected ones.
|
# including tracked ones and newly detected ones.
|
||||||
FeatureMeasurement[] features
|
FeatureMeasurement[] features
|
||||||
|
@ -3,12 +3,13 @@
|
|||||||
|
|
||||||
<name>msckf_vio</name>
|
<name>msckf_vio</name>
|
||||||
<version>0.0.1</version>
|
<version>0.0.1</version>
|
||||||
<description>Multi-State Constraint Kalman Filter - Photometric expansion</description>
|
<description>Multi-State Constraint Kalman Filter for Vision-aided Inertial Navigation</description>
|
||||||
|
|
||||||
<maintainer email="raphael@maenle.net">Raphael Maenle</maintainer>
|
<maintainer email="sunke.polyu@gmail.com">Ke Sun</maintainer>
|
||||||
<license>Penn Software License</license>
|
<license>Penn Software License</license>
|
||||||
|
|
||||||
<author email="raphael@maenle.net">Raphael Maenle</author>
|
<author email="sunke.polyu@gmail.com">Ke Sun</author>
|
||||||
|
<author email="kartikmohta@gmail.com">Kartik Mohta</author>
|
||||||
|
|
||||||
<buildtool_depend>catkin</buildtool_depend>
|
<buildtool_depend>catkin</buildtool_depend>
|
||||||
|
|
||||||
@ -18,7 +19,6 @@
|
|||||||
<depend>nav_msgs</depend>
|
<depend>nav_msgs</depend>
|
||||||
<depend>sensor_msgs</depend>
|
<depend>sensor_msgs</depend>
|
||||||
<depend>geometry_msgs</depend>
|
<depend>geometry_msgs</depend>
|
||||||
<depend>visualization_msgs</depend>
|
|
||||||
<depend>eigen_conversions</depend>
|
<depend>eigen_conversions</depend>
|
||||||
<depend>tf_conversions</depend>
|
<depend>tf_conversions</depend>
|
||||||
<depend>random_numbers</depend>
|
<depend>random_numbers</depend>
|
||||||
|
@ -1,97 +0,0 @@
|
|||||||
|
|
||||||
|
|
||||||
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
|
|
@ -1,82 +0,0 @@
|
|||||||
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_
|
|
@ -1,160 +0,0 @@
|
|||||||
#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,7 +17,6 @@
|
|||||||
#include <msckf_vio/TrackingInfo.h>
|
#include <msckf_vio/TrackingInfo.h>
|
||||||
#include <msckf_vio/image_processor.h>
|
#include <msckf_vio/image_processor.h>
|
||||||
#include <msckf_vio/utils.h>
|
#include <msckf_vio/utils.h>
|
||||||
#include <msckf_vio/image_handler.h>
|
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace cv;
|
using namespace cv;
|
||||||
@ -44,49 +43,49 @@ ImageProcessor::~ImageProcessor() {
|
|||||||
bool ImageProcessor::loadParameters() {
|
bool ImageProcessor::loadParameters() {
|
||||||
// Camera calibration parameters
|
// Camera calibration parameters
|
||||||
nh.param<string>("cam0/distortion_model",
|
nh.param<string>("cam0/distortion_model",
|
||||||
cam0.distortion_model, string("radtan"));
|
cam0_distortion_model, string("radtan"));
|
||||||
nh.param<string>("cam1/distortion_model",
|
nh.param<string>("cam1/distortion_model",
|
||||||
cam1.distortion_model, string("radtan"));
|
cam1_distortion_model, string("radtan"));
|
||||||
|
|
||||||
vector<int> cam0_resolution_temp(2);
|
vector<int> cam0_resolution_temp(2);
|
||||||
nh.getParam("cam0/resolution", cam0_resolution_temp);
|
nh.getParam("cam0/resolution", cam0_resolution_temp);
|
||||||
cam0.resolution[0] = cam0_resolution_temp[0];
|
cam0_resolution[0] = cam0_resolution_temp[0];
|
||||||
cam0.resolution[1] = cam0_resolution_temp[1];
|
cam0_resolution[1] = cam0_resolution_temp[1];
|
||||||
|
|
||||||
vector<int> cam1_resolution_temp(2);
|
vector<int> cam1_resolution_temp(2);
|
||||||
nh.getParam("cam1/resolution", cam1_resolution_temp);
|
nh.getParam("cam1/resolution", cam1_resolution_temp);
|
||||||
cam1.resolution[0] = cam1_resolution_temp[0];
|
cam1_resolution[0] = cam1_resolution_temp[0];
|
||||||
cam1.resolution[1] = cam1_resolution_temp[1];
|
cam1_resolution[1] = cam1_resolution_temp[1];
|
||||||
|
|
||||||
vector<double> cam0_intrinsics_temp(4);
|
vector<double> cam0_intrinsics_temp(4);
|
||||||
nh.getParam("cam0/intrinsics", cam0_intrinsics_temp);
|
nh.getParam("cam0/intrinsics", cam0_intrinsics_temp);
|
||||||
cam0.intrinsics[0] = cam0_intrinsics_temp[0];
|
cam0_intrinsics[0] = cam0_intrinsics_temp[0];
|
||||||
cam0.intrinsics[1] = cam0_intrinsics_temp[1];
|
cam0_intrinsics[1] = cam0_intrinsics_temp[1];
|
||||||
cam0.intrinsics[2] = cam0_intrinsics_temp[2];
|
cam0_intrinsics[2] = cam0_intrinsics_temp[2];
|
||||||
cam0.intrinsics[3] = cam0_intrinsics_temp[3];
|
cam0_intrinsics[3] = cam0_intrinsics_temp[3];
|
||||||
|
|
||||||
vector<double> cam1_intrinsics_temp(4);
|
vector<double> cam1_intrinsics_temp(4);
|
||||||
nh.getParam("cam1/intrinsics", cam1_intrinsics_temp);
|
nh.getParam("cam1/intrinsics", cam1_intrinsics_temp);
|
||||||
cam1.intrinsics[0] = cam1_intrinsics_temp[0];
|
cam1_intrinsics[0] = cam1_intrinsics_temp[0];
|
||||||
cam1.intrinsics[1] = cam1_intrinsics_temp[1];
|
cam1_intrinsics[1] = cam1_intrinsics_temp[1];
|
||||||
cam1.intrinsics[2] = cam1_intrinsics_temp[2];
|
cam1_intrinsics[2] = cam1_intrinsics_temp[2];
|
||||||
cam1.intrinsics[3] = cam1_intrinsics_temp[3];
|
cam1_intrinsics[3] = cam1_intrinsics_temp[3];
|
||||||
|
|
||||||
vector<double> cam0_distortion_coeffs_temp(4);
|
vector<double> cam0_distortion_coeffs_temp(4);
|
||||||
nh.getParam("cam0/distortion_coeffs",
|
nh.getParam("cam0/distortion_coeffs",
|
||||||
cam0_distortion_coeffs_temp);
|
cam0_distortion_coeffs_temp);
|
||||||
cam0.distortion_coeffs[0] = cam0_distortion_coeffs_temp[0];
|
cam0_distortion_coeffs[0] = cam0_distortion_coeffs_temp[0];
|
||||||
cam0.distortion_coeffs[1] = cam0_distortion_coeffs_temp[1];
|
cam0_distortion_coeffs[1] = cam0_distortion_coeffs_temp[1];
|
||||||
cam0.distortion_coeffs[2] = cam0_distortion_coeffs_temp[2];
|
cam0_distortion_coeffs[2] = cam0_distortion_coeffs_temp[2];
|
||||||
cam0.distortion_coeffs[3] = cam0_distortion_coeffs_temp[3];
|
cam0_distortion_coeffs[3] = cam0_distortion_coeffs_temp[3];
|
||||||
|
|
||||||
vector<double> cam1_distortion_coeffs_temp(4);
|
vector<double> cam1_distortion_coeffs_temp(4);
|
||||||
nh.getParam("cam1/distortion_coeffs",
|
nh.getParam("cam1/distortion_coeffs",
|
||||||
cam1_distortion_coeffs_temp);
|
cam1_distortion_coeffs_temp);
|
||||||
cam1.distortion_coeffs[0] = cam1_distortion_coeffs_temp[0];
|
cam1_distortion_coeffs[0] = cam1_distortion_coeffs_temp[0];
|
||||||
cam1.distortion_coeffs[1] = cam1_distortion_coeffs_temp[1];
|
cam1_distortion_coeffs[1] = cam1_distortion_coeffs_temp[1];
|
||||||
cam1.distortion_coeffs[2] = cam1_distortion_coeffs_temp[2];
|
cam1_distortion_coeffs[2] = cam1_distortion_coeffs_temp[2];
|
||||||
cam1.distortion_coeffs[3] = cam1_distortion_coeffs_temp[3];
|
cam1_distortion_coeffs[3] = cam1_distortion_coeffs_temp[3];
|
||||||
|
|
||||||
cv::Mat T_imu_cam0 = utils::getTransformCV(nh, "cam0/T_cam_imu");
|
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)));
|
cv::Matx33d R_imu_cam0(T_imu_cam0(cv::Rect(0,0,3,3)));
|
||||||
@ -124,27 +123,27 @@ bool ImageProcessor::loadParameters() {
|
|||||||
processor_config.stereo_threshold, 3);
|
processor_config.stereo_threshold, 3);
|
||||||
|
|
||||||
ROS_INFO("===========================================");
|
ROS_INFO("===========================================");
|
||||||
ROS_INFO("cam0.resolution: %d, %d",
|
ROS_INFO("cam0_resolution: %d, %d",
|
||||||
cam0.resolution[0], cam0.resolution[1]);
|
cam0_resolution[0], cam0_resolution[1]);
|
||||||
ROS_INFO("cam0_intrinscs: %f, %f, %f, %f",
|
ROS_INFO("cam0_intrinscs: %f, %f, %f, %f",
|
||||||
cam0.intrinsics[0], cam0.intrinsics[1],
|
cam0_intrinsics[0], cam0_intrinsics[1],
|
||||||
cam0.intrinsics[2], cam0.intrinsics[3]);
|
cam0_intrinsics[2], cam0_intrinsics[3]);
|
||||||
ROS_INFO("cam0.distortion_model: %s",
|
ROS_INFO("cam0_distortion_model: %s",
|
||||||
cam0.distortion_model.c_str());
|
cam0_distortion_model.c_str());
|
||||||
ROS_INFO("cam0_distortion_coefficients: %f, %f, %f, %f",
|
ROS_INFO("cam0_distortion_coefficients: %f, %f, %f, %f",
|
||||||
cam0.distortion_coeffs[0], cam0.distortion_coeffs[1],
|
cam0_distortion_coeffs[0], cam0_distortion_coeffs[1],
|
||||||
cam0.distortion_coeffs[2], cam0.distortion_coeffs[3]);
|
cam0_distortion_coeffs[2], cam0_distortion_coeffs[3]);
|
||||||
|
|
||||||
ROS_INFO("cam1.resolution: %d, %d",
|
ROS_INFO("cam1_resolution: %d, %d",
|
||||||
cam1.resolution[0], cam1.resolution[1]);
|
cam1_resolution[0], cam1_resolution[1]);
|
||||||
ROS_INFO("cam1_intrinscs: %f, %f, %f, %f",
|
ROS_INFO("cam1_intrinscs: %f, %f, %f, %f",
|
||||||
cam1.intrinsics[0], cam1.intrinsics[1],
|
cam1_intrinsics[0], cam1_intrinsics[1],
|
||||||
cam1.intrinsics[2], cam1.intrinsics[3]);
|
cam1_intrinsics[2], cam1_intrinsics[3]);
|
||||||
ROS_INFO("cam1.distortion_model: %s",
|
ROS_INFO("cam1_distortion_model: %s",
|
||||||
cam1.distortion_model.c_str());
|
cam1_distortion_model.c_str());
|
||||||
ROS_INFO("cam1_distortion_coefficients: %f, %f, %f, %f",
|
ROS_INFO("cam1_distortion_coefficients: %f, %f, %f, %f",
|
||||||
cam1.distortion_coeffs[0], cam1.distortion_coeffs[1],
|
cam1_distortion_coeffs[0], cam1_distortion_coeffs[1],
|
||||||
cam1.distortion_coeffs[2], cam1.distortion_coeffs[3]);
|
cam1_distortion_coeffs[2], cam1_distortion_coeffs[3]);
|
||||||
|
|
||||||
cout << R_imu_cam0 << endl;
|
cout << R_imu_cam0 << endl;
|
||||||
cout << t_imu_cam0.t() << endl;
|
cout << t_imu_cam0.t() << endl;
|
||||||
@ -171,6 +170,10 @@ bool ImageProcessor::loadParameters() {
|
|||||||
processor_config.ransac_threshold);
|
processor_config.ransac_threshold);
|
||||||
ROS_INFO("stereo_threshold: %f",
|
ROS_INFO("stereo_threshold: %f",
|
||||||
processor_config.stereo_threshold);
|
processor_config.stereo_threshold);
|
||||||
|
ROS_INFO("OpenCV Major Version: %d",
|
||||||
|
CV_MAJOR_VERSION);
|
||||||
|
ROS_INFO("OpenCV Minor Version: %d",
|
||||||
|
CV_MINOR_VERSION);
|
||||||
ROS_INFO("===========================================");
|
ROS_INFO("===========================================");
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -201,6 +204,13 @@ bool ImageProcessor::initialize() {
|
|||||||
detector_ptr = FastFeatureDetector::create(
|
detector_ptr = FastFeatureDetector::create(
|
||||||
processor_config.fast_threshold);
|
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;
|
if (!createRosIO()) return false;
|
||||||
ROS_INFO("Finish creating ROS IO...");
|
ROS_INFO("Finish creating ROS IO...");
|
||||||
|
|
||||||
@ -220,7 +230,9 @@ void ImageProcessor::stereoCallback(
|
|||||||
sensor_msgs::image_encodings::MONO8);
|
sensor_msgs::image_encodings::MONO8);
|
||||||
|
|
||||||
// Build the image pyramids once since they're used at multiple places
|
// Build the image pyramids once since they're used at multiple places
|
||||||
createImagePyramids();
|
|
||||||
|
// removed due to alternate cuda construct
|
||||||
|
//createImagePyramids();
|
||||||
|
|
||||||
// Detect features in the first frame.
|
// Detect features in the first frame.
|
||||||
if (is_first_img) {
|
if (is_first_img) {
|
||||||
@ -297,6 +309,7 @@ void ImageProcessor::imuCallback(
|
|||||||
|
|
||||||
void ImageProcessor::createImagePyramids() {
|
void ImageProcessor::createImagePyramids() {
|
||||||
const Mat& curr_cam0_img = cam0_curr_img_ptr->image;
|
const Mat& curr_cam0_img = cam0_curr_img_ptr->image;
|
||||||
|
// TODO: build cuda optical flow
|
||||||
buildOpticalFlowPyramid(
|
buildOpticalFlowPyramid(
|
||||||
curr_cam0_img, curr_cam0_pyramid_,
|
curr_cam0_img, curr_cam0_pyramid_,
|
||||||
Size(processor_config.patch_size, processor_config.patch_size),
|
Size(processor_config.patch_size, processor_config.patch_size),
|
||||||
@ -304,6 +317,7 @@ void ImageProcessor::createImagePyramids() {
|
|||||||
BORDER_CONSTANT, false);
|
BORDER_CONSTANT, false);
|
||||||
|
|
||||||
const Mat& curr_cam1_img = cam1_curr_img_ptr->image;
|
const Mat& curr_cam1_img = cam1_curr_img_ptr->image;
|
||||||
|
// TODO: build cuda optical flow
|
||||||
buildOpticalFlowPyramid(
|
buildOpticalFlowPyramid(
|
||||||
curr_cam1_img, curr_cam1_pyramid_,
|
curr_cam1_img, curr_cam1_pyramid_,
|
||||||
Size(processor_config.patch_size, processor_config.patch_size),
|
Size(processor_config.patch_size, processor_config.patch_size),
|
||||||
@ -390,6 +404,7 @@ void ImageProcessor::predictFeatureTracking(
|
|||||||
const cv::Matx33f& R_p_c,
|
const cv::Matx33f& R_p_c,
|
||||||
const cv::Vec4d& intrinsics,
|
const cv::Vec4d& intrinsics,
|
||||||
vector<cv::Point2f>& compensated_pts) {
|
vector<cv::Point2f>& compensated_pts) {
|
||||||
|
|
||||||
// Return directly if there are no input features.
|
// Return directly if there are no input features.
|
||||||
if (input_pts.size() == 0) {
|
if (input_pts.size() == 0) {
|
||||||
compensated_pts.clear();
|
compensated_pts.clear();
|
||||||
@ -420,6 +435,7 @@ void ImageProcessor::trackFeatures() {
|
|||||||
cam0_curr_img_ptr->image.rows / processor_config.grid_row;
|
cam0_curr_img_ptr->image.rows / processor_config.grid_row;
|
||||||
static int grid_width =
|
static int grid_width =
|
||||||
cam0_curr_img_ptr->image.cols / processor_config.grid_col;
|
cam0_curr_img_ptr->image.cols / processor_config.grid_col;
|
||||||
|
|
||||||
// Compute a rough relative rotation which takes a vector
|
// Compute a rough relative rotation which takes a vector
|
||||||
// from the previous frame to the current frame.
|
// from the previous frame to the current frame.
|
||||||
Matx33f cam0_R_p_c;
|
Matx33f cam0_R_p_c;
|
||||||
@ -453,8 +469,10 @@ void ImageProcessor::trackFeatures() {
|
|||||||
vector<unsigned char> track_inliers(0);
|
vector<unsigned char> track_inliers(0);
|
||||||
|
|
||||||
predictFeatureTracking(prev_cam0_points,
|
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(
|
calcOpticalFlowPyrLK(
|
||||||
prev_cam0_pyramid_, curr_cam0_pyramid_,
|
prev_cam0_pyramid_, curr_cam0_pyramid_,
|
||||||
prev_cam0_points, curr_cam0_points,
|
prev_cam0_points, curr_cam0_points,
|
||||||
@ -465,6 +483,25 @@ void ImageProcessor::trackFeatures() {
|
|||||||
processor_config.max_iteration,
|
processor_config.max_iteration,
|
||||||
processor_config.track_precision),
|
processor_config.track_precision),
|
||||||
cv::OPTFLOW_USE_INITIAL_FLOW);
|
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
|
// Mark those tracked points out of the image region
|
||||||
// as untracked.
|
// as untracked.
|
||||||
@ -548,14 +585,14 @@ void ImageProcessor::trackFeatures() {
|
|||||||
// Step 2 and 3: RANSAC on temporal image pairs of cam0 and cam1.
|
// Step 2 and 3: RANSAC on temporal image pairs of cam0 and cam1.
|
||||||
vector<int> cam0_ransac_inliers(0);
|
vector<int> cam0_ransac_inliers(0);
|
||||||
twoPointRansac(prev_matched_cam0_points, curr_matched_cam0_points,
|
twoPointRansac(prev_matched_cam0_points, curr_matched_cam0_points,
|
||||||
cam0_R_p_c, cam0.intrinsics, cam0.distortion_model,
|
cam0_R_p_c, cam0_intrinsics, cam0_distortion_model,
|
||||||
cam0.distortion_coeffs, processor_config.ransac_threshold,
|
cam0_distortion_coeffs, processor_config.ransac_threshold,
|
||||||
0.99, cam0_ransac_inliers);
|
0.99, cam0_ransac_inliers);
|
||||||
|
|
||||||
vector<int> cam1_ransac_inliers(0);
|
vector<int> cam1_ransac_inliers(0);
|
||||||
twoPointRansac(prev_matched_cam1_points, curr_matched_cam1_points,
|
twoPointRansac(prev_matched_cam1_points, curr_matched_cam1_points,
|
||||||
cam1_R_p_c, cam1.intrinsics, cam1.distortion_model,
|
cam1_R_p_c, cam1_intrinsics, cam1_distortion_model,
|
||||||
cam1.distortion_coeffs, processor_config.ransac_threshold,
|
cam1_distortion_coeffs, processor_config.ransac_threshold,
|
||||||
0.99, cam1_ransac_inliers);
|
0.99, cam1_ransac_inliers);
|
||||||
|
|
||||||
// Number of features after ransac.
|
// Number of features after ransac.
|
||||||
@ -609,6 +646,7 @@ void ImageProcessor::stereoMatch(
|
|||||||
const vector<cv::Point2f>& cam0_points,
|
const vector<cv::Point2f>& cam0_points,
|
||||||
vector<cv::Point2f>& cam1_points,
|
vector<cv::Point2f>& cam1_points,
|
||||||
vector<unsigned char>& inlier_markers) {
|
vector<unsigned char>& inlier_markers) {
|
||||||
|
|
||||||
if (cam0_points.size() == 0) return;
|
if (cam0_points.size() == 0) return;
|
||||||
|
|
||||||
if(cam1_points.size() == 0) {
|
if(cam1_points.size() == 0) {
|
||||||
@ -616,15 +654,31 @@ void ImageProcessor::stereoMatch(
|
|||||||
// rotation from stereo extrinsics
|
// rotation from stereo extrinsics
|
||||||
const cv::Matx33d R_cam0_cam1 = R_cam1_imu.t() * R_cam0_imu;
|
const cv::Matx33d R_cam0_cam1 = R_cam1_imu.t() * R_cam0_imu;
|
||||||
vector<cv::Point2f> cam0_points_undistorted;
|
vector<cv::Point2f> cam0_points_undistorted;
|
||||||
image_handler::undistortPoints(cam0_points, cam0.intrinsics, cam0.distortion_model,
|
undistortPoints(cam0_points, cam0_intrinsics, cam0_distortion_model,
|
||||||
cam0.distortion_coeffs, cam0_points_undistorted,
|
cam0_distortion_coeffs, cam0_points_undistorted,
|
||||||
R_cam0_cam1);
|
R_cam0_cam1);
|
||||||
|
cam1_points = distortPoints(cam0_points_undistorted, cam1_intrinsics,
|
||||||
cam1_points = image_handler::distortPoints(cam0_points_undistorted, cam1.intrinsics,
|
cam1_distortion_model, cam1_distortion_coeffs);
|
||||||
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.
|
// Track features using LK optical flow method.
|
||||||
|
/*
|
||||||
calcOpticalFlowPyrLK(curr_cam0_pyramid_, curr_cam1_pyramid_,
|
calcOpticalFlowPyrLK(curr_cam0_pyramid_, curr_cam1_pyramid_,
|
||||||
cam0_points, cam1_points,
|
cam0_points, cam1_points,
|
||||||
inlier_markers, noArray(),
|
inlier_markers, noArray(),
|
||||||
@ -634,7 +688,7 @@ void ImageProcessor::stereoMatch(
|
|||||||
processor_config.max_iteration,
|
processor_config.max_iteration,
|
||||||
processor_config.track_precision),
|
processor_config.track_precision),
|
||||||
cv::OPTFLOW_USE_INITIAL_FLOW);
|
cv::OPTFLOW_USE_INITIAL_FLOW);
|
||||||
|
*/
|
||||||
// Mark those tracked points out of the image region
|
// Mark those tracked points out of the image region
|
||||||
// as untracked.
|
// as untracked.
|
||||||
for (int i = 0; i < cam1_points.size(); ++i) {
|
for (int i = 0; i < cam1_points.size(); ++i) {
|
||||||
@ -661,16 +715,16 @@ void ImageProcessor::stereoMatch(
|
|||||||
// essential matrix.
|
// essential matrix.
|
||||||
vector<cv::Point2f> cam0_points_undistorted(0);
|
vector<cv::Point2f> cam0_points_undistorted(0);
|
||||||
vector<cv::Point2f> cam1_points_undistorted(0);
|
vector<cv::Point2f> cam1_points_undistorted(0);
|
||||||
image_handler::undistortPoints(
|
undistortPoints(
|
||||||
cam0_points, cam0.intrinsics, cam0.distortion_model,
|
cam0_points, cam0_intrinsics, cam0_distortion_model,
|
||||||
cam0.distortion_coeffs, cam0_points_undistorted);
|
cam0_distortion_coeffs, cam0_points_undistorted);
|
||||||
image_handler::undistortPoints(
|
undistortPoints(
|
||||||
cam1_points, cam1.intrinsics, cam1.distortion_model,
|
cam1_points, cam1_intrinsics, cam1_distortion_model,
|
||||||
cam1.distortion_coeffs, cam1_points_undistorted);
|
cam1_distortion_coeffs, cam1_points_undistorted);
|
||||||
|
|
||||||
double norm_pixel_unit = 4.0 / (
|
double norm_pixel_unit = 4.0 / (
|
||||||
cam0.intrinsics[0]+cam0.intrinsics[1]+
|
cam0_intrinsics[0]+cam0_intrinsics[1]+
|
||||||
cam1.intrinsics[0]+cam1.intrinsics[1]);
|
cam1_intrinsics[0]+cam1_intrinsics[1]);
|
||||||
|
|
||||||
for (int i = 0; i < cam0_points_undistorted.size(); ++i) {
|
for (int i = 0; i < cam0_points_undistorted.size(); ++i) {
|
||||||
if (inlier_markers[i] == 0) continue;
|
if (inlier_markers[i] == 0) continue;
|
||||||
@ -697,8 +751,8 @@ void ImageProcessor::addNewFeatures() {
|
|||||||
cam0_curr_img_ptr->image.rows / processor_config.grid_row;
|
cam0_curr_img_ptr->image.rows / processor_config.grid_row;
|
||||||
static int grid_width =
|
static int grid_width =
|
||||||
cam0_curr_img_ptr->image.cols / processor_config.grid_col;
|
cam0_curr_img_ptr->image.cols / processor_config.grid_col;
|
||||||
// Create a mask to avoid redetecting existing features.
|
|
||||||
|
|
||||||
|
// Create a mask to avoid redetecting existing features.
|
||||||
Mat mask(curr_img.rows, curr_img.cols, CV_8U, Scalar(1));
|
Mat mask(curr_img.rows, curr_img.cols, CV_8U, Scalar(1));
|
||||||
|
|
||||||
for (const auto& features : *curr_features_ptr) {
|
for (const auto& features : *curr_features_ptr) {
|
||||||
@ -718,6 +772,7 @@ void ImageProcessor::addNewFeatures() {
|
|||||||
mask(row_range, col_range) = 0;
|
mask(row_range, col_range) = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Detect new features.
|
// Detect new features.
|
||||||
vector<KeyPoint> new_features(0);
|
vector<KeyPoint> new_features(0);
|
||||||
detector_ptr->detect(curr_img, new_features, mask);
|
detector_ptr->detect(curr_img, new_features, mask);
|
||||||
@ -732,6 +787,7 @@ void ImageProcessor::addNewFeatures() {
|
|||||||
new_feature_sieve[
|
new_feature_sieve[
|
||||||
row*processor_config.grid_col+col].push_back(feature);
|
row*processor_config.grid_col+col].push_back(feature);
|
||||||
}
|
}
|
||||||
|
|
||||||
new_features.clear();
|
new_features.clear();
|
||||||
for (auto& item : new_feature_sieve) {
|
for (auto& item : new_feature_sieve) {
|
||||||
if (item.size() > processor_config.grid_max_feature_num) {
|
if (item.size() > processor_config.grid_max_feature_num) {
|
||||||
@ -744,6 +800,7 @@ void ImageProcessor::addNewFeatures() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
int detected_new_features = new_features.size();
|
int detected_new_features = new_features.size();
|
||||||
|
|
||||||
// Find the stereo matched points for the newly
|
// Find the stereo matched points for the newly
|
||||||
// detected features.
|
// detected features.
|
||||||
vector<cv::Point2f> cam0_points(new_features.size());
|
vector<cv::Point2f> cam0_points(new_features.size());
|
||||||
@ -771,6 +828,7 @@ void ImageProcessor::addNewFeatures() {
|
|||||||
static_cast<double>(detected_new_features) < 0.1)
|
static_cast<double>(detected_new_features) < 0.1)
|
||||||
ROS_WARN("Images at [%f] seems unsynced...",
|
ROS_WARN("Images at [%f] seems unsynced...",
|
||||||
cam0_curr_img_ptr->header.stamp.toSec());
|
cam0_curr_img_ptr->header.stamp.toSec());
|
||||||
|
|
||||||
// Group the features into grids
|
// Group the features into grids
|
||||||
GridFeatures grid_new_features;
|
GridFeatures grid_new_features;
|
||||||
for (int code = 0; code <
|
for (int code = 0; code <
|
||||||
@ -792,6 +850,7 @@ void ImageProcessor::addNewFeatures() {
|
|||||||
new_feature.cam1_point = cam1_point;
|
new_feature.cam1_point = cam1_point;
|
||||||
grid_new_features[code].push_back(new_feature);
|
grid_new_features[code].push_back(new_feature);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Sort the new features in each grid based on its response.
|
// Sort the new features in each grid based on its response.
|
||||||
for (auto& item : grid_new_features)
|
for (auto& item : grid_new_features)
|
||||||
std::sort(item.second.begin(), item.second.end(),
|
std::sort(item.second.begin(), item.second.end(),
|
||||||
@ -841,6 +900,73 @@ void ImageProcessor::pruneGridFeatures() {
|
|||||||
return;
|
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(
|
void ImageProcessor::integrateImuData(
|
||||||
Matx33f& cam0_R_p_c, Matx33f& cam1_R_p_c) {
|
Matx33f& cam0_R_p_c, Matx33f& cam1_R_p_c) {
|
||||||
// Find the start and the end limit within the imu msg buffer.
|
// Find the start and the end limit within the imu msg buffer.
|
||||||
@ -892,6 +1018,7 @@ void ImageProcessor::integrateImuData(
|
|||||||
void ImageProcessor::rescalePoints(
|
void ImageProcessor::rescalePoints(
|
||||||
vector<Point2f>& pts1, vector<Point2f>& pts2,
|
vector<Point2f>& pts1, vector<Point2f>& pts2,
|
||||||
float& scaling_factor) {
|
float& scaling_factor) {
|
||||||
|
|
||||||
scaling_factor = 0.0f;
|
scaling_factor = 0.0f;
|
||||||
|
|
||||||
for (int i = 0; i < pts1.size(); ++i) {
|
for (int i = 0; i < pts1.size(); ++i) {
|
||||||
@ -921,7 +1048,7 @@ void ImageProcessor::twoPointRansac(
|
|||||||
|
|
||||||
// Check the size of input point size.
|
// Check the size of input point size.
|
||||||
if (pts1.size() != pts2.size())
|
if (pts1.size() != pts2.size())
|
||||||
ROS_ERROR("Sets of different size (%lu and %lu) are used...",
|
ROS_ERROR("Sets of different size (%i and %i) are used...",
|
||||||
pts1.size(), pts2.size());
|
pts1.size(), pts2.size());
|
||||||
|
|
||||||
double norm_pixel_unit = 2.0 / (intrinsics[0]+intrinsics[1]);
|
double norm_pixel_unit = 2.0 / (intrinsics[0]+intrinsics[1]);
|
||||||
@ -935,10 +1062,10 @@ void ImageProcessor::twoPointRansac(
|
|||||||
// Undistort all the points.
|
// Undistort all the points.
|
||||||
vector<Point2f> pts1_undistorted(pts1.size());
|
vector<Point2f> pts1_undistorted(pts1.size());
|
||||||
vector<Point2f> pts2_undistorted(pts2.size());
|
vector<Point2f> pts2_undistorted(pts2.size());
|
||||||
image_handler::undistortPoints(
|
undistortPoints(
|
||||||
pts1, intrinsics, distortion_model,
|
pts1, intrinsics, distortion_model,
|
||||||
distortion_coeffs, pts1_undistorted);
|
distortion_coeffs, pts1_undistorted);
|
||||||
image_handler::undistortPoints(
|
undistortPoints(
|
||||||
pts2, intrinsics, distortion_model,
|
pts2, intrinsics, distortion_model,
|
||||||
distortion_coeffs, pts2_undistorted);
|
distortion_coeffs, pts2_undistorted);
|
||||||
|
|
||||||
@ -1156,6 +1283,7 @@ void ImageProcessor::twoPointRansac(
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ImageProcessor::publish() {
|
void ImageProcessor::publish() {
|
||||||
|
|
||||||
// Publish features.
|
// Publish features.
|
||||||
CameraMeasurementPtr feature_msg_ptr(new CameraMeasurement);
|
CameraMeasurementPtr feature_msg_ptr(new CameraMeasurement);
|
||||||
feature_msg_ptr->header.stamp = cam0_curr_img_ptr->header.stamp;
|
feature_msg_ptr->header.stamp = cam0_curr_img_ptr->header.stamp;
|
||||||
@ -1175,12 +1303,12 @@ void ImageProcessor::publish() {
|
|||||||
vector<Point2f> curr_cam0_points_undistorted(0);
|
vector<Point2f> curr_cam0_points_undistorted(0);
|
||||||
vector<Point2f> curr_cam1_points_undistorted(0);
|
vector<Point2f> curr_cam1_points_undistorted(0);
|
||||||
|
|
||||||
image_handler::undistortPoints(
|
undistortPoints(
|
||||||
curr_cam0_points, cam0.intrinsics, cam0.distortion_model,
|
curr_cam0_points, cam0_intrinsics, cam0_distortion_model,
|
||||||
cam0.distortion_coeffs, curr_cam0_points_undistorted);
|
cam0_distortion_coeffs, curr_cam0_points_undistorted);
|
||||||
image_handler::undistortPoints(
|
undistortPoints(
|
||||||
curr_cam1_points, cam1.intrinsics, cam1.distortion_model,
|
curr_cam1_points, cam1_intrinsics, cam1_distortion_model,
|
||||||
cam1.distortion_coeffs, curr_cam1_points_undistorted);
|
cam1_distortion_coeffs, curr_cam1_points_undistorted);
|
||||||
|
|
||||||
for (int i = 0; i < curr_ids.size(); ++i) {
|
for (int i = 0; i < curr_ids.size(); ++i) {
|
||||||
feature_msg_ptr->features.push_back(FeatureMeasurement());
|
feature_msg_ptr->features.push_back(FeatureMeasurement());
|
||||||
|
1118
src/msckf_vio.cpp
1118
src/msckf_vio.cpp
File diff suppressed because it is too large
Load Diff
@ -11,6 +11,20 @@
|
|||||||
namespace msckf_vio {
|
namespace msckf_vio {
|
||||||
namespace utils {
|
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,
|
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
|
||||||
const std::string &field) {
|
const std::string &field) {
|
||||||
Eigen::Isometry3d T;
|
Eigen::Isometry3d T;
|
||||||
|
Reference in New Issue
Block a user