Compare commits
	
		
			45 Commits
		
	
	
		
			LKcuda
			...
			photometry
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
| 6e151510cf | |||
| 8bebf99c37 | |||
| 82cd2c6771 | |||
| 0be7047928 | |||
| 2f130685c8 | |||
| 8ff0e9d816 | |||
| 976108bffe | |||
| 2aef2089aa | |||
| 0f96c916f1 | |||
| 05d277c4f4 | |||
| 9c7f67d2fd | |||
| 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_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
 | 
				
			||||||
@@ -79,6 +80,7 @@ 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}
 | 
				
			||||||
@@ -87,6 +89,7 @@ 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
 | 
				
			||||||
@@ -106,6 +109,7 @@ 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}
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										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"
 | 
					#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.
 | 
				
			||||||
@@ -35,6 +63,9 @@ 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
 | 
				
			||||||
 
 | 
				
			|||||||
@@ -15,11 +15,18 @@
 | 
				
			|||||||
#include <Eigen/Dense>
 | 
					#include <Eigen/Dense>
 | 
				
			||||||
#include <Eigen/Geometry>
 | 
					#include <Eigen/Geometry>
 | 
				
			||||||
#include <Eigen/StdVector>
 | 
					#include <Eigen/StdVector>
 | 
				
			||||||
 | 
					#include <math.h>
 | 
				
			||||||
 | 
					#include <visualization_msgs/Marker.h>
 | 
				
			||||||
 | 
					#include <visualization_msgs/MarkerArray.h>
 | 
				
			||||||
 | 
					#include <geometry_msgs/Point.h>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#include "image_handler.h"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include "math_utils.hpp"
 | 
					#include "math_utils.hpp"
 | 
				
			||||||
#include "imu_state.h"
 | 
					#include "imu_state.h"
 | 
				
			||||||
#include "cam_state.h"
 | 
					#include "cam_state.h"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
namespace msckf_vio {
 | 
					namespace msckf_vio {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/*
 | 
					/*
 | 
				
			||||||
@@ -57,11 +64,11 @@ struct Feature {
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
  // Constructors for the struct.
 | 
					  // Constructors for the struct.
 | 
				
			||||||
  Feature(): id(0), position(Eigen::Vector3d::Zero()),
 | 
					  Feature(): id(0), position(Eigen::Vector3d::Zero()),
 | 
				
			||||||
    is_initialized(false) {}
 | 
					    is_initialized(false), is_anchored(false) {}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  Feature(const FeatureIDType& new_id): id(new_id),
 | 
					  Feature(const FeatureIDType& new_id): id(new_id),
 | 
				
			||||||
    position(Eigen::Vector3d::Zero()),
 | 
					    position(Eigen::Vector3d::Zero()),
 | 
				
			||||||
    is_initialized(false) {}
 | 
					    is_initialized(false), is_anchored(false) {}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  /*
 | 
					  /*
 | 
				
			||||||
   * @brief cost Compute the cost of the camera observations
 | 
					   * @brief cost Compute the cost of the camera observations
 | 
				
			||||||
@@ -114,6 +121,28 @@ struct Feature {
 | 
				
			|||||||
  inline bool checkMotion(
 | 
					  inline bool checkMotion(
 | 
				
			||||||
      const CamStateServer& cam_states) const;
 | 
					      const CamStateServer& cam_states) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  /*
 | 
				
			||||||
 | 
					   * @brief AnchorPixelToPosition projects an undistorted point in the
 | 
				
			||||||
 | 
					   *        anchor frame back into the real world using the rho calculated 
 | 
				
			||||||
 | 
					   *        based on featur position
 | 
				
			||||||
 | 
					   */
 | 
				
			||||||
 | 
					  inline Eigen::Vector3d AnchorPixelToPosition(cv::Point2f in_p, const CameraCalibration& cam);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  /*
 | 
				
			||||||
 | 
					   * @brief InitializeAnchor generates the NxN patch around the
 | 
				
			||||||
 | 
					   *        feature in the Anchor image
 | 
				
			||||||
 | 
					   * @param cam_states: A map containing all recorded images 
 | 
				
			||||||
 | 
					   *        currently presented in the camera state vector
 | 
				
			||||||
 | 
					   * @return the irradiance of the Anchor NxN Patch 
 | 
				
			||||||
 | 
					   * @return True if the Anchor can be estimated
 | 
				
			||||||
 | 
					   */
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  bool initializeAnchor(
 | 
				
			||||||
 | 
					   const CameraCalibration& cam, int N);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  /*
 | 
					  /*
 | 
				
			||||||
   * @brief InitializePosition Intialize the feature position
 | 
					   * @brief InitializePosition Intialize the feature position
 | 
				
			||||||
   *    based on all current available measurements.
 | 
					   *    based on all current available measurements.
 | 
				
			||||||
@@ -129,6 +158,67 @@ struct Feature {
 | 
				
			|||||||
      const CamStateServer& cam_states);
 | 
					      const CamStateServer& cam_states);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					cv::Point2f pixelDistanceAt(
 | 
				
			||||||
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  const CameraCalibration& cam,
 | 
				
			||||||
 | 
					                  Eigen::Vector3d& in_p) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					/*
 | 
				
			||||||
 | 
					*  @brief project PositionToCamera Takes a 3d position in a world frame
 | 
				
			||||||
 | 
					*         and projects it into the passed camera frame using pinhole projection
 | 
				
			||||||
 | 
					*         then distorts it using camera information to get 
 | 
				
			||||||
 | 
					*         the resulting distorted pixel position  
 | 
				
			||||||
 | 
					*/
 | 
				
			||||||
 | 
					  inline cv::Point2f projectPositionToCamera(
 | 
				
			||||||
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  const CameraCalibration& cam,
 | 
				
			||||||
 | 
					                  Eigen::Vector3d& in_p) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  /*
 | 
				
			||||||
 | 
					  * @brief IrradianceAnchorPatch_Camera returns irradiance values
 | 
				
			||||||
 | 
					  *        of the Anchor Patch position in a camera frame
 | 
				
			||||||
 | 
					  *
 | 
				
			||||||
 | 
					  */
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  bool estimate_FrameIrradiance(
 | 
				
			||||||
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  CameraCalibration& cam0,
 | 
				
			||||||
 | 
					                  std::vector<double>& anchorPatch_estimate,
 | 
				
			||||||
 | 
					                  IlluminationParameter& estimatedIllumination) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  bool MarkerGeneration(
 | 
				
			||||||
 | 
					                  ros::Publisher& marker_pub,
 | 
				
			||||||
 | 
					                  const CamStateServer& cam_states) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  bool VisualizePatch(
 | 
				
			||||||
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  CameraCalibration& cam0,
 | 
				
			||||||
 | 
					                  const std::vector<double> photo_r,
 | 
				
			||||||
 | 
					                  std::stringstream& ss) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  /* @brief takes a pure pixel position (1m from image)
 | 
				
			||||||
 | 
					  * converts to actual pixel value and returns patch irradiance
 | 
				
			||||||
 | 
					  * around this pixel
 | 
				
			||||||
 | 
					  */
 | 
				
			||||||
 | 
					  void PatchAroundPurePixel(cv::Point2f p, 
 | 
				
			||||||
 | 
					                               int N,
 | 
				
			||||||
 | 
					                               const CameraCalibration& cam, 
 | 
				
			||||||
 | 
					                               const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                               std::vector<float>& return_i) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  /*
 | 
				
			||||||
 | 
					  * @brief Irradiance returns irradiance value of a pixel
 | 
				
			||||||
 | 
					  */
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  inline float PixelIrradiance(cv::Point2f pose, cv::Mat image) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // An unique identifier for the feature.
 | 
					  // An unique identifier for the feature.
 | 
				
			||||||
  // In case of long time running, the variable
 | 
					  // In case of long time running, the variable
 | 
				
			||||||
  // type of id is set to FeatureIDType in order
 | 
					  // type of id is set to FeatureIDType in order
 | 
				
			||||||
@@ -144,13 +234,30 @@ struct Feature {
 | 
				
			|||||||
    Eigen::aligned_allocator<
 | 
					    Eigen::aligned_allocator<
 | 
				
			||||||
      std::pair<const StateIDType, Eigen::Vector4d> > > observations;
 | 
					      std::pair<const StateIDType, Eigen::Vector4d> > > observations;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // NxN Patch of Anchor Image
 | 
				
			||||||
 | 
					  std::vector<double> anchorPatch;
 | 
				
			||||||
 | 
					  std::vector<cv::Point2f> anchorPatch_ideal;
 | 
				
			||||||
 | 
					  std::vector<cv::Point2f> anchorPatch_real;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Position of NxN Patch in 3D space in anchor camera frame
 | 
				
			||||||
 | 
					  std::vector<Eigen::Vector3d> anchorPatch_3d;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Anchor Isometry
 | 
				
			||||||
 | 
					  Eigen::Isometry3d T_anchor_w;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // 3d postion of the feature in the world frame.
 | 
					  // 3d postion of the feature in the world frame.
 | 
				
			||||||
  Eigen::Vector3d position;
 | 
					  Eigen::Vector3d position;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // inverse depth representation
 | 
				
			||||||
 | 
					  double anchor_rho;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // A indicator to show if the 3d postion of the feature
 | 
					  // A indicator to show if the 3d postion of the feature
 | 
				
			||||||
  // has been initialized or not.
 | 
					  // has been initialized or not.
 | 
				
			||||||
  bool is_initialized;
 | 
					  bool is_initialized;
 | 
				
			||||||
 | 
					  bool is_anchored;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::Point2f anchor_center_pos;
 | 
				
			||||||
 | 
					  cv::Point2f undist_anchor_center_pos;
 | 
				
			||||||
  // Noise for a normalized feature measurement.
 | 
					  // Noise for a normalized feature measurement.
 | 
				
			||||||
  static double observation_noise;
 | 
					  static double observation_noise;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -167,7 +274,8 @@ typedef std::map<FeatureIDType, Feature, std::less<int>,
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
void Feature::cost(const Eigen::Isometry3d& T_c0_ci,
 | 
					void Feature::cost(const Eigen::Isometry3d& T_c0_ci,
 | 
				
			||||||
    const Eigen::Vector3d& x, const Eigen::Vector2d& z,
 | 
					    const Eigen::Vector3d& x, const Eigen::Vector2d& z,
 | 
				
			||||||
    double& e) const {
 | 
					    double& e) const 
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
  // Compute hi1, hi2, and hi3 as Equation (37).
 | 
					  // Compute hi1, hi2, and hi3 as Equation (37).
 | 
				
			||||||
  const double& alpha = x(0);
 | 
					  const double& alpha = x(0);
 | 
				
			||||||
  const double& beta = x(1);
 | 
					  const double& beta = x(1);
 | 
				
			||||||
@@ -190,7 +298,8 @@ void Feature::cost(const Eigen::Isometry3d& T_c0_ci,
 | 
				
			|||||||
void Feature::jacobian(const Eigen::Isometry3d& T_c0_ci,
 | 
					void Feature::jacobian(const Eigen::Isometry3d& T_c0_ci,
 | 
				
			||||||
    const Eigen::Vector3d& x, const Eigen::Vector2d& z,
 | 
					    const Eigen::Vector3d& x, const Eigen::Vector2d& z,
 | 
				
			||||||
    Eigen::Matrix<double, 2, 3>& J, Eigen::Vector2d& r,
 | 
					    Eigen::Matrix<double, 2, 3>& J, Eigen::Vector2d& r,
 | 
				
			||||||
    double& w) const {
 | 
					    double& w) const 
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // Compute hi1, hi2, and hi3 as Equation (37).
 | 
					  // Compute hi1, hi2, and hi3 as Equation (37).
 | 
				
			||||||
  const double& alpha = x(0);
 | 
					  const double& alpha = x(0);
 | 
				
			||||||
@@ -227,7 +336,8 @@ void Feature::jacobian(const Eigen::Isometry3d& T_c0_ci,
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
void Feature::generateInitialGuess(
 | 
					void Feature::generateInitialGuess(
 | 
				
			||||||
    const Eigen::Isometry3d& T_c1_c2, const Eigen::Vector2d& z1,
 | 
					    const Eigen::Isometry3d& T_c1_c2, const Eigen::Vector2d& z1,
 | 
				
			||||||
    const Eigen::Vector2d& z2, Eigen::Vector3d& p) const {
 | 
					    const Eigen::Vector2d& z2, Eigen::Vector3d& p) const 
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
  // Construct a least square problem to solve the depth.
 | 
					  // Construct a least square problem to solve the depth.
 | 
				
			||||||
  Eigen::Vector3d m = T_c1_c2.linear() * Eigen::Vector3d(z1(0), z1(1), 1.0);
 | 
					  Eigen::Vector3d m = T_c1_c2.linear() * Eigen::Vector3d(z1(0), z1(1), 1.0);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -247,8 +357,8 @@ void Feature::generateInitialGuess(
 | 
				
			|||||||
  return;
 | 
					  return;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
bool Feature::checkMotion(
 | 
					bool Feature::checkMotion(const CamStateServer& cam_states) const 
 | 
				
			||||||
    const CamStateServer& cam_states) const {
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  const StateIDType& first_cam_id = observations.begin()->first;
 | 
					  const StateIDType& first_cam_id = observations.begin()->first;
 | 
				
			||||||
  const StateIDType& last_cam_id = (--observations.end())->first;
 | 
					  const StateIDType& last_cam_id = (--observations.end())->first;
 | 
				
			||||||
@@ -290,8 +400,524 @@ bool Feature::checkMotion(
 | 
				
			|||||||
  else return false;
 | 
					  else return false;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
bool Feature::initializePosition(
 | 
					bool Feature::estimate_FrameIrradiance(
 | 
				
			||||||
    const CamStateServer& cam_states) {
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  CameraCalibration& cam0,
 | 
				
			||||||
 | 
					                  std::vector<double>& anchorPatch_estimate,
 | 
				
			||||||
 | 
					                  IlluminationParameter& estimated_illumination) const
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  // get irradiance of patch in anchor frame
 | 
				
			||||||
 | 
					  // subtract estimated b and divide by a of anchor frame
 | 
				
			||||||
 | 
					  // muliply by a and add b of this frame
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  auto anchor = observations.begin();
 | 
				
			||||||
 | 
					  if(cam0.moving_window.find(anchor->first) == cam0.moving_window.end())
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    std::cout << "anchor not in buffer anymore!" << std::endl;
 | 
				
			||||||
 | 
					    return false;
 | 
				
			||||||
 | 
					  } 
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  double anchorExposureTime_ms = cam0.moving_window.find(anchor->first)->second.exposureTime_ms;
 | 
				
			||||||
 | 
					  double frameExposureTime_ms = cam0.moving_window.find(cam_state_id)->second.exposureTime_ms;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  double a_A = anchorExposureTime_ms;
 | 
				
			||||||
 | 
					  double b_A = 0;
 | 
				
			||||||
 | 
					  double a_l = frameExposureTime_ms;
 | 
				
			||||||
 | 
					  double b_l = 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  estimated_illumination.frame_gain = a_l;
 | 
				
			||||||
 | 
					  estimated_illumination.frame_bias = b_l;
 | 
				
			||||||
 | 
					  estimated_illumination.feature_gain = 1;
 | 
				
			||||||
 | 
					  estimated_illumination.feature_bias = 0;
 | 
				
			||||||
 | 
					  //printf("frames: %lld, %lld\n", anchor->first, cam_state_id);
 | 
				
			||||||
 | 
					  //printf("exposure: %f, %f\n", a_A, a_l);
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  for (double anchorPixel : anchorPatch)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    float irradiance = (anchorPixel - b_A) / a_A ;
 | 
				
			||||||
 | 
					    anchorPatch_estimate.push_back(irradiance);
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					// generates markers for every camera position/observation
 | 
				
			||||||
 | 
					// and estimated feature/path position
 | 
				
			||||||
 | 
					bool Feature::MarkerGeneration(
 | 
				
			||||||
 | 
					                  ros::Publisher& marker_pub,
 | 
				
			||||||
 | 
					                  const CamStateServer& cam_states) const
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  visualization_msgs::MarkerArray ma;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // add all camera states used for estimation
 | 
				
			||||||
 | 
					  int count = 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(auto observation : observations)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    visualization_msgs::Marker marker;
 | 
				
			||||||
 | 
					    marker.header.frame_id = "world";
 | 
				
			||||||
 | 
					    marker.header.stamp = ros::Time::now();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.ns = "cameras";
 | 
				
			||||||
 | 
					    marker.id = count++;
 | 
				
			||||||
 | 
					    marker.type =  visualization_msgs::Marker::ARROW;
 | 
				
			||||||
 | 
					    marker.action = visualization_msgs::Marker::ADD;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.pose.position.x = cam_states.find(observation.first)->second.position(0);
 | 
				
			||||||
 | 
					    marker.pose.position.y = cam_states.find(observation.first)->second.position(1);
 | 
				
			||||||
 | 
					    marker.pose.position.z = cam_states.find(observation.first)->second.position(2);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    // rotate form x to z axis
 | 
				
			||||||
 | 
					    Eigen::Vector4d q = quaternionMultiplication(Eigen::Vector4d(0, -0.707, 0, 0.707), cam_states.find(observation.first)->second.orientation);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.pose.orientation.x = q(0);
 | 
				
			||||||
 | 
					    marker.pose.orientation.y = q(1);
 | 
				
			||||||
 | 
					    marker.pose.orientation.z = q(2);
 | 
				
			||||||
 | 
					    marker.pose.orientation.w = q(3);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.scale.x = 0.15;
 | 
				
			||||||
 | 
					    marker.scale.y = 0.05;
 | 
				
			||||||
 | 
					    marker.scale.z = 0.05;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    if(count == 1)
 | 
				
			||||||
 | 
					    {
 | 
				
			||||||
 | 
					        marker.color.r = 0.0f;
 | 
				
			||||||
 | 
					        marker.color.g = 0.0f;
 | 
				
			||||||
 | 
					        marker.color.b = 1.0f;
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					    else
 | 
				
			||||||
 | 
					    {
 | 
				
			||||||
 | 
					        marker.color.r = 0.0f;
 | 
				
			||||||
 | 
					        marker.color.g = 1.0f;
 | 
				
			||||||
 | 
					        marker.color.b = 0.0f;
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					    marker.color.a = 1.0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.lifetime = ros::Duration(0);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    ma.markers.push_back(marker);
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // 'delete' any existing cameras (make invisible)
 | 
				
			||||||
 | 
					  for(int i = count; i < 20; i++)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    visualization_msgs::Marker marker;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.header.frame_id = "world";
 | 
				
			||||||
 | 
					    marker.header.stamp = ros::Time::now();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.ns = "cameras";
 | 
				
			||||||
 | 
					    marker.id = i;
 | 
				
			||||||
 | 
					    marker.type =  visualization_msgs::Marker::ARROW;
 | 
				
			||||||
 | 
					    marker.action = visualization_msgs::Marker::ADD;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.pose.orientation.w = 1;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.color.a = 0.0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    marker.lifetime = ros::Duration(1);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    ma.markers.push_back(marker);
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //generate feature patch points position
 | 
				
			||||||
 | 
					  visualization_msgs::Marker marker;
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  marker.header.frame_id = "world";
 | 
				
			||||||
 | 
					  marker.header.stamp = ros::Time::now();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  marker.ns = "patch";
 | 
				
			||||||
 | 
					  marker.id = 0;
 | 
				
			||||||
 | 
					  marker.type = visualization_msgs::Marker::POINTS;
 | 
				
			||||||
 | 
					  marker.action = visualization_msgs::Marker::ADD;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  marker.pose.orientation.w = 1;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  marker.scale.x = 0.02;
 | 
				
			||||||
 | 
					  marker.scale.y = 0.02;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  marker.color.r = 1.0f;
 | 
				
			||||||
 | 
					  marker.color.g = 0.0f;
 | 
				
			||||||
 | 
					  marker.color.b = 0.0f;
 | 
				
			||||||
 | 
					  marker.color.a = 1.0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(auto point : anchorPatch_3d)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    geometry_msgs::Point p;
 | 
				
			||||||
 | 
					    p.x = point(0);
 | 
				
			||||||
 | 
					    p.y = point(1);
 | 
				
			||||||
 | 
					    p.z = point(2);
 | 
				
			||||||
 | 
					    marker.points.push_back(p);
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					  ma.markers.push_back(marker);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  marker_pub.publish(ma);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					bool Feature::VisualizePatch(
 | 
				
			||||||
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  CameraCalibration& cam0,
 | 
				
			||||||
 | 
					                  const std::vector<double> photo_r,
 | 
				
			||||||
 | 
					                  std::stringstream& ss) const
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  double rescale = 1;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //visu - anchor
 | 
				
			||||||
 | 
					  auto anchor = observations.begin();
 | 
				
			||||||
 | 
					  cv::Mat anchorImage = cam0.moving_window.find(anchor->first)->second.image;
 | 
				
			||||||
 | 
					  cv::Mat dottedFrame(anchorImage.size(), CV_8UC3);
 | 
				
			||||||
 | 
					  cv::cvtColor(anchorImage, dottedFrame, CV_GRAY2RGB);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // visualize the true anchor points (the surrounding of the original measurements)
 | 
				
			||||||
 | 
					  for(auto point : anchorPatch_real)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    // visu - feature
 | 
				
			||||||
 | 
					    cv::Point xs(point.x, point.y);
 | 
				
			||||||
 | 
					    cv::Point ys(point.x, point.y);
 | 
				
			||||||
 | 
					    cv::rectangle(dottedFrame, xs, ys, cv::Scalar(0,255,255));
 | 
				
			||||||
 | 
					  }  
 | 
				
			||||||
 | 
					  cam0.featureVisu = dottedFrame.clone(); 
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // visu - feature
 | 
				
			||||||
 | 
					  cv::Mat current_image = cam0.moving_window.find(cam_state_id)->second.image;
 | 
				
			||||||
 | 
					  cv::cvtColor(current_image, dottedFrame, CV_GRAY2RGB);
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  // set position in frame 
 | 
				
			||||||
 | 
					  // save irradiance of projection
 | 
				
			||||||
 | 
					  std::vector<double> projectionPatch;
 | 
				
			||||||
 | 
					  for(auto point : anchorPatch_3d)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    cv::Point2f p_in_c0 = projectPositionToCamera(cam_state, cam_state_id, cam0, point);
 | 
				
			||||||
 | 
					    projectionPatch.push_back(PixelIrradiance(p_in_c0, current_image));
 | 
				
			||||||
 | 
					    // visu - feature
 | 
				
			||||||
 | 
					    cv::Point xs(p_in_c0.x, p_in_c0.y);
 | 
				
			||||||
 | 
					    cv::Point ys(p_in_c0.x, p_in_c0.y);
 | 
				
			||||||
 | 
					    cv::rectangle(dottedFrame, xs, ys, cv::Scalar(0,255,0));
 | 
				
			||||||
 | 
					  }  
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::hconcat(cam0.featureVisu, dottedFrame, cam0.featureVisu);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // patches visualization
 | 
				
			||||||
 | 
					  int N = sqrt(anchorPatch_3d.size());
 | 
				
			||||||
 | 
					  int scale = 30;
 | 
				
			||||||
 | 
					  cv::Mat irradianceFrame(anchorImage.size(), CV_8UC3, cv::Scalar(255, 240, 255));
 | 
				
			||||||
 | 
					  cv::resize(irradianceFrame, irradianceFrame, cv::Size(), rescale, rescale);
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  // irradiance grid anchor
 | 
				
			||||||
 | 
					  std::stringstream namer;
 | 
				
			||||||
 | 
					  namer << "anchor";
 | 
				
			||||||
 | 
					  cv::putText(irradianceFrame, namer.str() , cvPoint(30, 25), 
 | 
				
			||||||
 | 
					    cv::FONT_HERSHEY_COMPLEX_SMALL, 0.8, cvScalar(0,0,0), 1, CV_AA);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(int i = 0; i<N; i++)
 | 
				
			||||||
 | 
					    for(int j = 0; j<N; j++)
 | 
				
			||||||
 | 
					      cv::rectangle(irradianceFrame, 
 | 
				
			||||||
 | 
					                    cv::Point(30+scale*(i+1), 30+scale*j), 
 | 
				
			||||||
 | 
					                    cv::Point(30+scale*i, 30+scale*(j+1)), 
 | 
				
			||||||
 | 
					                    cv::Scalar(anchorPatch[i*N+j]*255, anchorPatch[i*N+j]*255, anchorPatch[i*N+j]*255),  
 | 
				
			||||||
 | 
					                    CV_FILLED);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // irradiance grid projection
 | 
				
			||||||
 | 
					  namer.str(std::string());
 | 
				
			||||||
 | 
					  namer << "projection";
 | 
				
			||||||
 | 
					  cv::putText(irradianceFrame, namer.str(), cvPoint(30, 45+scale*N), 
 | 
				
			||||||
 | 
					    cv::FONT_HERSHEY_COMPLEX_SMALL, 0.8, cvScalar(0,0,0), 1, CV_AA);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(int i = 0; i<N; i++)
 | 
				
			||||||
 | 
					    for(int j = 0; j<N ; j++)
 | 
				
			||||||
 | 
					      cv::rectangle(irradianceFrame, 
 | 
				
			||||||
 | 
					                    cv::Point(30+scale*(i+1), 50+scale*(N+j)), 
 | 
				
			||||||
 | 
					                    cv::Point(30+scale*(i), 50+scale*(N+j+1)), 
 | 
				
			||||||
 | 
					                    cv::Scalar(projectionPatch[i*N+j]*255, projectionPatch[i*N+j]*255, projectionPatch[i*N+j]*255),  
 | 
				
			||||||
 | 
					                    CV_FILLED);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // true irradiance at feature
 | 
				
			||||||
 | 
					  // get current observation
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  namer.str(std::string());
 | 
				
			||||||
 | 
					  namer << "feature";
 | 
				
			||||||
 | 
					  cv::putText(irradianceFrame, namer.str() , cvPoint(30, 65+scale*2*N), 
 | 
				
			||||||
 | 
					    cv::FONT_HERSHEY_COMPLEX_SMALL, 0.8, cvScalar(0,0,0), 1, CV_AA);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::Point2f p_f(observations.find(cam_state_id)->second(0),observations.find(cam_state_id)->second(1));
 | 
				
			||||||
 | 
					  // move to real pixels
 | 
				
			||||||
 | 
					  p_f = image_handler::distortPoint(p_f, cam0.intrinsics, cam0.distortion_model, cam0.distortion_coeffs);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(int i = 0; i<N; i++)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					    for(int j = 0; j<N ; j++)
 | 
				
			||||||
 | 
					    {
 | 
				
			||||||
 | 
					      float irr = PixelIrradiance(cv::Point2f(p_f.x + (i-(N-1)/2), p_f.y + (j-(N-1)/2)), current_image);
 | 
				
			||||||
 | 
					      cv::rectangle(irradianceFrame, 
 | 
				
			||||||
 | 
					                    cv::Point(30+scale*(i+1), 70+scale*(2*N+j)), 
 | 
				
			||||||
 | 
					                    cv::Point(30+scale*(i), 70+scale*(2*N+j+1)), 
 | 
				
			||||||
 | 
					                    cv::Scalar(irr*255, irr*255, irr*255),  
 | 
				
			||||||
 | 
					                    CV_FILLED);
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // residual grid projection, positive - red, negative - blue colored 
 | 
				
			||||||
 | 
					  namer.str(std::string());
 | 
				
			||||||
 | 
					  namer << "residual";
 | 
				
			||||||
 | 
					  cv::putText(irradianceFrame, namer.str() , cvPoint(30+scale*N, scale*N/2-5), 
 | 
				
			||||||
 | 
					    cv::FONT_HERSHEY_COMPLEX_SMALL, 0.8, cvScalar(0,0,0), 1, CV_AA);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(int i = 0; i<N; i++)
 | 
				
			||||||
 | 
					    for(int j = 0; j<N; j++)
 | 
				
			||||||
 | 
					      if(photo_r[i*N+j]>0)
 | 
				
			||||||
 | 
					        cv::rectangle(irradianceFrame, 
 | 
				
			||||||
 | 
					                      cv::Point(40+scale*(N+i+1), 15+scale*(N/2+j)), 
 | 
				
			||||||
 | 
					                      cv::Point(40+scale*(N+i), 15+scale*(N/2+j+1)), 
 | 
				
			||||||
 | 
					                      cv::Scalar(255 - photo_r[i*N+j]*255, 255 - photo_r[i*N+j]*255, 255),  
 | 
				
			||||||
 | 
					                      CV_FILLED);
 | 
				
			||||||
 | 
					      else
 | 
				
			||||||
 | 
					        cv::rectangle(irradianceFrame, 
 | 
				
			||||||
 | 
					                      cv::Point(40+scale*(N+i+1), 15+scale*(N/2+j)), 
 | 
				
			||||||
 | 
					                      cv::Point(40+scale*(N+i), 15+scale*(N/2+j+1)), 
 | 
				
			||||||
 | 
					                      cv::Scalar(255, 255 + photo_r[i*N+j]*255, 255 + photo_r[i*N+j]*255), 
 | 
				
			||||||
 | 
					                      CV_FILLED);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // gradient arrow
 | 
				
			||||||
 | 
					  /*
 | 
				
			||||||
 | 
					  cv::arrowedLine(irradianceFrame,
 | 
				
			||||||
 | 
					                  cv::Point(30+scale*(N/2 +0.5), 50+scale*(N+(N/2)+0.5)),
 | 
				
			||||||
 | 
					                  cv::Point(30+scale*(N/2+0.5)+scale*gradientVector.x, 50+scale*(N+(N/2)+0.5)+scale*gradientVector.y),
 | 
				
			||||||
 | 
					                  cv::Scalar(100, 0, 255),
 | 
				
			||||||
 | 
					                  1);
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  // residual gradient direction
 | 
				
			||||||
 | 
					  cv::arrowedLine(irradianceFrame,
 | 
				
			||||||
 | 
					                  cv::Point(40+scale*(N+N/2+0.5), 15+scale*((N-0.5))),
 | 
				
			||||||
 | 
					                  cv::Point(40+scale*(N+N/2+0.5)+scale*residualVector.x, 15+scale*(N-0.5)+scale*residualVector.y),
 | 
				
			||||||
 | 
					                  cv::Scalar(0, 255, 175),
 | 
				
			||||||
 | 
					                  3);
 | 
				
			||||||
 | 
					                  
 | 
				
			||||||
 | 
					  */
 | 
				
			||||||
 | 
					  cv::hconcat(cam0.featureVisu, irradianceFrame, cam0.featureVisu);
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					    
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // visualize position of used observations and resulting feature position
 | 
				
			||||||
 | 
					  /*
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::Mat positionFrame(anchorImage.size(), CV_8UC3, cv::Scalar(255, 240, 255));
 | 
				
			||||||
 | 
					  cv::resize(positionFrame, positionFrame, cv::Size(), rescale, rescale);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // draw world zero
 | 
				
			||||||
 | 
					  cv::line(positionFrame,
 | 
				
			||||||
 | 
					          cv::Point(20,20),
 | 
				
			||||||
 | 
					          cv::Point(20,30),
 | 
				
			||||||
 | 
					          cv::Scalar(0,0,255),
 | 
				
			||||||
 | 
					          CV_FILLED);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::line(positionFrame,
 | 
				
			||||||
 | 
					          cv::Point(20,20),
 | 
				
			||||||
 | 
					          cv::Point(30,20),
 | 
				
			||||||
 | 
					          cv::Scalar(255,0,0),
 | 
				
			||||||
 | 
					          CV_FILLED);
 | 
				
			||||||
 | 
					  // for every observation, get cam state
 | 
				
			||||||
 | 
					  for(auto obs : observations)
 | 
				
			||||||
 | 
					  {
 | 
				
			||||||
 | 
					      cv::line(positionFrame,
 | 
				
			||||||
 | 
					        cv::Point(20,20),
 | 
				
			||||||
 | 
					        cv::Point(30,20),
 | 
				
			||||||
 | 
					        cv::Scalar(255,0,0),
 | 
				
			||||||
 | 
					        CV_FILLED);
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // draw, x y position and arrow with direction - write z next to it
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::resize(cam0.featureVisu, cam0.featureVisu, cv::Size(), rescale, rescale);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::hconcat(cam0.featureVisu, positionFrame, cam0.featureVisu);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  */
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // write feature position
 | 
				
			||||||
 | 
					  std::stringstream pos_s;
 | 
				
			||||||
 | 
					  pos_s << "u: " << observations.begin()->second(0) << " v: " << observations.begin()->second(1);
 | 
				
			||||||
 | 
					  cv::putText(cam0.featureVisu, ss.str() , cvPoint(anchorImage.rows + 100, anchorImage.cols - 30), 
 | 
				
			||||||
 | 
					    cv::FONT_HERSHEY_COMPLEX_SMALL, 0.8, cvScalar(200,200,250), 1, CV_AA);
 | 
				
			||||||
 | 
					  // create line?
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //save image
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  std::stringstream loc;
 | 
				
			||||||
 | 
					 // loc << "/home/raphael/dev/MSCKF_ws/img/feature_" << std::to_string(ros::Time::now().toSec()) << ".jpg";
 | 
				
			||||||
 | 
					  //cv::imwrite(loc.str(), cam0.featureVisu);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::imshow("patch", cam0.featureVisu);
 | 
				
			||||||
 | 
					  cvWaitKey(0);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					void Feature::PatchAroundPurePixel(cv::Point2f p, 
 | 
				
			||||||
 | 
					                               int N,
 | 
				
			||||||
 | 
					                               const CameraCalibration& cam, 
 | 
				
			||||||
 | 
					                               const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                               std::vector<float>& return_i) const
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  int n = (int)(N-1)/2;
 | 
				
			||||||
 | 
					  cv::Mat image = cam.moving_window.find(cam_state_id)->second.image;
 | 
				
			||||||
 | 
					  cv::Point2f img_p = image_handler::distortPoint(p, 
 | 
				
			||||||
 | 
					                                                cam.intrinsics, 
 | 
				
			||||||
 | 
					                                                cam.distortion_model, 
 | 
				
			||||||
 | 
					                                                cam.distortion_coeffs);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(double u_run = -n; u_run <= n; u_run++)
 | 
				
			||||||
 | 
					    for(double v_run = -n; v_run <= n; v_run++)
 | 
				
			||||||
 | 
					      return_i.push_back(PixelIrradiance(cv::Point2f(img_p.x+u_run, img_p.y+v_run), image));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					float Feature::PixelIrradiance(cv::Point2f pose, cv::Mat image) const
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  return ((float)image.at<uint8_t>(pose.y, pose.x))/255;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					cv::Point2f Feature::pixelDistanceAt(
 | 
				
			||||||
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  const CameraCalibration& cam,
 | 
				
			||||||
 | 
					                  Eigen::Vector3d& in_p) const
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::Point2f cam_p = projectPositionToCamera(cam_state, cam_state_id, cam, in_p);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // create vector of patch in pixel plane
 | 
				
			||||||
 | 
					  std::vector<cv::Point2f> surroundingPoints;
 | 
				
			||||||
 | 
					  surroundingPoints.push_back(cv::Point2f(cam_p.x+1, cam_p.y));
 | 
				
			||||||
 | 
					  surroundingPoints.push_back(cv::Point2f(cam_p.x-1, cam_p.y));
 | 
				
			||||||
 | 
					  surroundingPoints.push_back(cv::Point2f(cam_p.x, cam_p.y+1));
 | 
				
			||||||
 | 
					  surroundingPoints.push_back(cv::Point2f(cam_p.x, cam_p.y-1));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  std::vector<cv::Point2f> pure;
 | 
				
			||||||
 | 
					  image_handler::undistortPoints(surroundingPoints, 
 | 
				
			||||||
 | 
					                                cam.intrinsics, 
 | 
				
			||||||
 | 
					                                cam.distortion_model, 
 | 
				
			||||||
 | 
					                                cam.distortion_coeffs, 
 | 
				
			||||||
 | 
					                                pure); 
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // returns the absolute pixel distance at pixels one metres away
 | 
				
			||||||
 | 
					  cv::Point2f distance(fabs(pure[0].x - pure[1].x), fabs(pure[2].y - pure[3].y));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  return distance;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					cv::Point2f Feature::projectPositionToCamera(
 | 
				
			||||||
 | 
					                  const CAMState& cam_state,
 | 
				
			||||||
 | 
					                  const StateIDType& cam_state_id,
 | 
				
			||||||
 | 
					                  const CameraCalibration& cam,
 | 
				
			||||||
 | 
					                  Eigen::Vector3d& in_p) const
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  Eigen::Isometry3d T_c0_w;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::Point2f out_p;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // transfrom position to camera frame
 | 
				
			||||||
 | 
					  Eigen::Matrix3d R_w_c0 = quaternionToRotation(cam_state.orientation);
 | 
				
			||||||
 | 
					  const Eigen::Vector3d& t_c0_w = cam_state.position;
 | 
				
			||||||
 | 
					  Eigen::Vector3d p_c0 = R_w_c0 * (in_p-t_c0_w);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  out_p = cv::Point2f(p_c0(0)/p_c0(2), p_c0(1)/p_c0(2));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					 // if(cam_state_id == observations.begin()->first)
 | 
				
			||||||
 | 
					      //printf("undist:\n  \tproj pos: %f, %f\n\ttrue pos: %f, %f\n", out_p.x, out_p.y, undist_anchor_center_pos.x, undist_anchor_center_pos.y);
 | 
				
			||||||
 | 
					 
 | 
				
			||||||
 | 
					  cv::Point2f my_p = image_handler::distortPoint(out_p, 
 | 
				
			||||||
 | 
					                                                 cam.intrinsics, 
 | 
				
			||||||
 | 
					                                                 cam.distortion_model, 
 | 
				
			||||||
 | 
					                                                 cam.distortion_coeffs);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // printf("truPosition: %f, %f, %f\n", position.x(), position.y(), position.z());
 | 
				
			||||||
 | 
					  // printf("camPosition: %f, %f, %f\n", p_c0(0), p_c0(1), p_c0(2));
 | 
				
			||||||
 | 
					  // printf("Photo projection: %f, %f\n", my_p[0].x,  my_p[0].y);
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  return my_p;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					Eigen::Vector3d Feature::AnchorPixelToPosition(cv::Point2f in_p, const CameraCalibration& cam)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  // use undistorted position of point of interest
 | 
				
			||||||
 | 
					  // project it back into 3D space using pinhole model
 | 
				
			||||||
 | 
					  // save resulting NxN positions for this feature
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  Eigen::Vector3d PositionInCamera(in_p.x/anchor_rho, in_p.y/anchor_rho, 1/anchor_rho);
 | 
				
			||||||
 | 
					  Eigen::Vector3d PositionInWorld = T_anchor_w.linear()*PositionInCamera + T_anchor_w.translation();
 | 
				
			||||||
 | 
					  return PositionInWorld;
 | 
				
			||||||
 | 
					  //printf("%f, %f, %f\n",PositionInWorld[0], PositionInWorld[1], PositionInWorld[2]);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					//@test center projection must always be initial feature projection
 | 
				
			||||||
 | 
					bool Feature::initializeAnchor(const CameraCalibration& cam, int N)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //initialize patch Size
 | 
				
			||||||
 | 
					  int n = (int)(N-1)/2;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  auto anchor = observations.begin();
 | 
				
			||||||
 | 
					  if(cam.moving_window.find(anchor->first) == cam.moving_window.end())
 | 
				
			||||||
 | 
					    return false;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  cv::Mat anchorImage = cam.moving_window.find(anchor->first)->second.image;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  auto u = anchor->second(0);//*cam.intrinsics[0] + cam.intrinsics[2];
 | 
				
			||||||
 | 
					  auto v = anchor->second(1);//*cam.intrinsics[1] + cam.intrinsics[3];
 | 
				
			||||||
 | 
					  
 | 
				
			||||||
 | 
					  //testing
 | 
				
			||||||
 | 
					  undist_anchor_center_pos = cv::Point2f(u,v);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //for NxN patch pixels around feature
 | 
				
			||||||
 | 
					  int count = 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // get feature in undistorted pixel space
 | 
				
			||||||
 | 
					  // this only reverts from 'pure' space into undistorted pixel space using camera matrix
 | 
				
			||||||
 | 
					  cv::Point2f und_pix_p = image_handler::distortPoint(cv::Point2f(u, v), 
 | 
				
			||||||
 | 
					                                                    cam.intrinsics, 
 | 
				
			||||||
 | 
					                                                    cam.distortion_model, 
 | 
				
			||||||
 | 
					                                                    cam.distortion_coeffs);
 | 
				
			||||||
 | 
					  // create vector of patch in pixel plane
 | 
				
			||||||
 | 
					  for(double u_run = -n; u_run <= n; u_run++)
 | 
				
			||||||
 | 
					    for(double v_run = -n; v_run <= n; v_run++)
 | 
				
			||||||
 | 
					      anchorPatch_real.push_back(cv::Point2f(und_pix_p.x+u_run, und_pix_p.y+v_run));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //create undistorted pure points    
 | 
				
			||||||
 | 
					  image_handler::undistortPoints(anchorPatch_real,
 | 
				
			||||||
 | 
					                                cam.intrinsics,
 | 
				
			||||||
 | 
					                                cam.distortion_model,
 | 
				
			||||||
 | 
					                                cam.distortion_coeffs,
 | 
				
			||||||
 | 
					                                anchorPatch_ideal);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // save anchor position for later visualisaztion
 | 
				
			||||||
 | 
					  anchor_center_pos = anchorPatch_real[(N*N-1)/2];
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // save true pixel Patch position
 | 
				
			||||||
 | 
					  for(auto point : anchorPatch_real)
 | 
				
			||||||
 | 
					    if(point.x - n < 0 || point.x + n >= cam.resolution(0) || point.y - n < 0 || point.y + n >= cam.resolution(1))
 | 
				
			||||||
 | 
					      return false;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for(auto point : anchorPatch_real)
 | 
				
			||||||
 | 
					    anchorPatch.push_back(PixelIrradiance(point, anchorImage));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // project patch pixel to 3D space in camera  coordinate system
 | 
				
			||||||
 | 
					  for(auto point : anchorPatch_ideal)
 | 
				
			||||||
 | 
					    anchorPatch_3d.push_back(AnchorPixelToPosition(point, cam));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  is_anchored = true;
 | 
				
			||||||
 | 
					  return true;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					/*
 | 
				
			||||||
 | 
					bool Feature::initializeRho(const CamStateServer& cam_states) {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // Organize camera poses and feature observations properly.
 | 
					  // Organize camera poses and feature observations properly.
 | 
				
			||||||
  std::vector<Eigen::Isometry3d,
 | 
					  std::vector<Eigen::Isometry3d,
 | 
				
			||||||
    Eigen::aligned_allocator<Eigen::Isometry3d> > cam_poses(0);
 | 
					    Eigen::aligned_allocator<Eigen::Isometry3d> > cam_poses(0);
 | 
				
			||||||
@@ -327,6 +953,7 @@ bool Feature::initializePosition(
 | 
				
			|||||||
  // vector from the first camera frame in the buffer to this
 | 
					  // vector from the first camera frame in the buffer to this
 | 
				
			||||||
  // camera frame.
 | 
					  // camera frame.
 | 
				
			||||||
  Eigen::Isometry3d T_c0_w = cam_poses[0];
 | 
					  Eigen::Isometry3d T_c0_w = cam_poses[0];
 | 
				
			||||||
 | 
					  T_anchor_w = T_c0_w;
 | 
				
			||||||
  for (auto& pose : cam_poses)
 | 
					  for (auto& pose : cam_poses)
 | 
				
			||||||
    pose = pose.inverse() * T_c0_w;
 | 
					    pose = pose.inverse() * T_c0_w;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -427,6 +1054,9 @@ bool Feature::initializePosition(
 | 
				
			|||||||
    }
 | 
					    }
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //save inverse depth distance from camera
 | 
				
			||||||
 | 
					  anchor_rho = solution(2);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // Convert the feature position to the world frame.
 | 
					  // Convert the feature position to the world frame.
 | 
				
			||||||
  position = T_c0_w.linear()*final_position + T_c0_w.translation();
 | 
					  position = T_c0_w.linear()*final_position + T_c0_w.translation();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -435,6 +1065,157 @@ bool Feature::initializePosition(
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
  return is_valid_solution;
 | 
					  return is_valid_solution;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					*/
 | 
				
			||||||
 | 
					bool Feature::initializePosition(const CamStateServer& cam_states) {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Organize camera poses and feature observations properly.
 | 
				
			||||||
 | 
					  std::vector<Eigen::Isometry3d,
 | 
				
			||||||
 | 
					    Eigen::aligned_allocator<Eigen::Isometry3d> > cam_poses(0);
 | 
				
			||||||
 | 
					  std::vector<Eigen::Vector2d,
 | 
				
			||||||
 | 
					    Eigen::aligned_allocator<Eigen::Vector2d> > measurements(0);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  for (auto& m : observations) {
 | 
				
			||||||
 | 
					    // TODO: This should be handled properly. Normally, the
 | 
				
			||||||
 | 
					    //    required camera states should all be available in
 | 
				
			||||||
 | 
					    //    the input cam_states buffer.
 | 
				
			||||||
 | 
					    auto cam_state_iter = cam_states.find(m.first);
 | 
				
			||||||
 | 
					    if (cam_state_iter == cam_states.end()) continue;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    // Add the measurement.
 | 
				
			||||||
 | 
					    measurements.push_back(m.second.head<2>());
 | 
				
			||||||
 | 
					    measurements.push_back(m.second.tail<2>());
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    // This camera pose will take a vector from this camera frame
 | 
				
			||||||
 | 
					    // to the world frame.
 | 
				
			||||||
 | 
					    Eigen::Isometry3d cam0_pose;
 | 
				
			||||||
 | 
					    cam0_pose.linear() = quaternionToRotation(
 | 
				
			||||||
 | 
					        cam_state_iter->second.orientation).transpose();
 | 
				
			||||||
 | 
					    cam0_pose.translation() = cam_state_iter->second.position;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    Eigen::Isometry3d cam1_pose;
 | 
				
			||||||
 | 
					    cam1_pose = cam0_pose * CAMState::T_cam0_cam1.inverse();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    cam_poses.push_back(cam0_pose);
 | 
				
			||||||
 | 
					    cam_poses.push_back(cam1_pose);
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // All camera poses should be modified such that it takes a
 | 
				
			||||||
 | 
					  // vector from the first camera frame in the buffer to this
 | 
				
			||||||
 | 
					  // camera frame.
 | 
				
			||||||
 | 
					  Eigen::Isometry3d T_c0_w = cam_poses[0];
 | 
				
			||||||
 | 
					  T_anchor_w = T_c0_w;
 | 
				
			||||||
 | 
					  for (auto& pose : cam_poses)
 | 
				
			||||||
 | 
					    pose = pose.inverse() * T_c0_w;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Generate initial guess
 | 
				
			||||||
 | 
					  Eigen::Vector3d initial_position(0.0, 0.0, 0.0);
 | 
				
			||||||
 | 
					  generateInitialGuess(cam_poses[cam_poses.size()-1], measurements[0],
 | 
				
			||||||
 | 
					      measurements[measurements.size()-1], initial_position);
 | 
				
			||||||
 | 
					  Eigen::Vector3d solution(
 | 
				
			||||||
 | 
					      initial_position(0)/initial_position(2),
 | 
				
			||||||
 | 
					      initial_position(1)/initial_position(2),
 | 
				
			||||||
 | 
					      1.0/initial_position(2));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Apply Levenberg-Marquart method to solve for the 3d position.
 | 
				
			||||||
 | 
					  double lambda = optimization_config.initial_damping;
 | 
				
			||||||
 | 
					  int inner_loop_cntr = 0;
 | 
				
			||||||
 | 
					  int outer_loop_cntr = 0;
 | 
				
			||||||
 | 
					  bool is_cost_reduced = false;
 | 
				
			||||||
 | 
					  double delta_norm = 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Compute the initial cost.
 | 
				
			||||||
 | 
					  double total_cost = 0.0;
 | 
				
			||||||
 | 
					  for (int i = 0; i < cam_poses.size(); ++i) {
 | 
				
			||||||
 | 
					    double this_cost = 0.0;
 | 
				
			||||||
 | 
					    cost(cam_poses[i], solution, measurements[i], this_cost);
 | 
				
			||||||
 | 
					    total_cost += this_cost;
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Outer loop.
 | 
				
			||||||
 | 
					  do {
 | 
				
			||||||
 | 
					    Eigen::Matrix3d A = Eigen::Matrix3d::Zero();
 | 
				
			||||||
 | 
					    Eigen::Vector3d b = Eigen::Vector3d::Zero();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    for (int i = 0; i < cam_poses.size(); ++i) {
 | 
				
			||||||
 | 
					      Eigen::Matrix<double, 2, 3> J;
 | 
				
			||||||
 | 
					      Eigen::Vector2d r;
 | 
				
			||||||
 | 
					      double w;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      jacobian(cam_poses[i], solution, measurements[i], J, r, w);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      if (w == 1) {
 | 
				
			||||||
 | 
					        A += J.transpose() * J;
 | 
				
			||||||
 | 
					        b += J.transpose() * r;
 | 
				
			||||||
 | 
					      } else {
 | 
				
			||||||
 | 
					        double w_square = w * w;
 | 
				
			||||||
 | 
					        A += w_square * J.transpose() * J;
 | 
				
			||||||
 | 
					        b += w_square * J.transpose() * r;
 | 
				
			||||||
 | 
					      }
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    // Inner loop.
 | 
				
			||||||
 | 
					    // Solve for the delta that can reduce the total cost.
 | 
				
			||||||
 | 
					    do {
 | 
				
			||||||
 | 
					      Eigen::Matrix3d damper = lambda * Eigen::Matrix3d::Identity();
 | 
				
			||||||
 | 
					      Eigen::Vector3d delta = (A+damper).ldlt().solve(b);
 | 
				
			||||||
 | 
					      Eigen::Vector3d new_solution = solution - delta;
 | 
				
			||||||
 | 
					      delta_norm = delta.norm();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      double new_cost = 0.0;
 | 
				
			||||||
 | 
					      for (int i = 0; i < cam_poses.size(); ++i) {
 | 
				
			||||||
 | 
					        double this_cost = 0.0;
 | 
				
			||||||
 | 
					        cost(cam_poses[i], new_solution, measurements[i], this_cost);
 | 
				
			||||||
 | 
					        new_cost += this_cost;
 | 
				
			||||||
 | 
					      }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      if (new_cost < total_cost) {
 | 
				
			||||||
 | 
					        is_cost_reduced = true;
 | 
				
			||||||
 | 
					        solution = new_solution;
 | 
				
			||||||
 | 
					        total_cost = new_cost;
 | 
				
			||||||
 | 
					        lambda = lambda/10 > 1e-10 ? lambda/10 : 1e-10;
 | 
				
			||||||
 | 
					      } else {
 | 
				
			||||||
 | 
					        is_cost_reduced = false;
 | 
				
			||||||
 | 
					        lambda = lambda*10 < 1e12 ? lambda*10 : 1e12;
 | 
				
			||||||
 | 
					      }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    } while (inner_loop_cntr++ <
 | 
				
			||||||
 | 
					        optimization_config.inner_loop_max_iteration && !is_cost_reduced);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					    inner_loop_cntr = 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  } while (outer_loop_cntr++ <
 | 
				
			||||||
 | 
					      optimization_config.outer_loop_max_iteration &&
 | 
				
			||||||
 | 
					      delta_norm > optimization_config.estimation_precision);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Covert the feature position from inverse depth
 | 
				
			||||||
 | 
					  // representation to its 3d coordinate.
 | 
				
			||||||
 | 
					  Eigen::Vector3d final_position(solution(0)/solution(2),
 | 
				
			||||||
 | 
					      solution(1)/solution(2), 1.0/solution(2));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Check if the solution is valid. Make sure the feature
 | 
				
			||||||
 | 
					  // is in front of every camera frame observing it.
 | 
				
			||||||
 | 
					  bool is_valid_solution = true;
 | 
				
			||||||
 | 
					  for (const auto& pose : cam_poses) {
 | 
				
			||||||
 | 
					    Eigen::Vector3d position =
 | 
				
			||||||
 | 
					      pose.linear()*final_position + pose.translation();
 | 
				
			||||||
 | 
					    if (position(2) <= 0) {
 | 
				
			||||||
 | 
					      is_valid_solution = false;
 | 
				
			||||||
 | 
					      break;
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  //save inverse depth distance from camera
 | 
				
			||||||
 | 
					  anchor_rho = solution(2);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  // Convert the feature position to the world frame.
 | 
				
			||||||
 | 
					  position = T_c0_w.linear()*final_position + T_c0_w.translation();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  if (is_valid_solution)
 | 
				
			||||||
 | 
					    is_initialized = true;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  return is_valid_solution;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
} // namespace msckf_vio
 | 
					} // namespace msckf_vio
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#endif // MSCKF_VIO_FEATURE_H
 | 
					#endif // MSCKF_VIO_FEATURE_H
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										51
									
								
								include/msckf_vio/image_handler.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										51
									
								
								include/msckf_vio/image_handler.h
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,51 @@
 | 
				
			|||||||
 | 
					#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/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>
 | 
				
			||||||
@@ -26,6 +22,8 @@
 | 
				
			|||||||
#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 {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/*
 | 
					/*
 | 
				
			||||||
@@ -312,7 +310,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(%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());
 | 
					          raw_vec.size(), markers.size());
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
    for (int i = 0; i < markers.size(); ++i) {
 | 
					    for (int i = 0; i < markers.size(); ++i) {
 | 
				
			||||||
@@ -336,15 +334,8 @@ private:
 | 
				
			|||||||
  std::vector<sensor_msgs::Imu> imu_msg_buffer;
 | 
					  std::vector<sensor_msgs::Imu> imu_msg_buffer;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // Camera calibration parameters
 | 
					  // Camera calibration parameters
 | 
				
			||||||
  std::string cam0_distortion_model;
 | 
					  CameraCalibration cam0;
 | 
				
			||||||
  cv::Vec2i cam0_resolution;
 | 
					  CameraCalibration cam1;
 | 
				
			||||||
  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;
 | 
				
			||||||
@@ -367,13 +358,6 @@ 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;
 | 
				
			||||||
 
 | 
				
			|||||||
@@ -13,6 +13,13 @@
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
namespace msckf_vio {
 | 
					namespace msckf_vio {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					inline double absoluted(double a){
 | 
				
			||||||
 | 
					  if(a>0)
 | 
				
			||||||
 | 
					    return a;
 | 
				
			||||||
 | 
					  else return -a;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/*
 | 
					/*
 | 
				
			||||||
 *  @brief Create a skew-symmetric matrix from a 3-element vector.
 | 
					 *  @brief Create a skew-symmetric matrix from a 3-element vector.
 | 
				
			||||||
 *  @note Performs the operation:
 | 
					 *  @note Performs the operation:
 | 
				
			||||||
@@ -43,6 +50,50 @@ 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,11 +14,17 @@
 | 
				
			|||||||
#include <string>
 | 
					#include <string>
 | 
				
			||||||
#include <Eigen/Dense>
 | 
					#include <Eigen/Dense>
 | 
				
			||||||
#include <Eigen/Geometry>
 | 
					#include <Eigen/Geometry>
 | 
				
			||||||
 | 
					#include <math.h>
 | 
				
			||||||
#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>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -27,6 +33,13 @@
 | 
				
			|||||||
#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>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#define PI 3.14159265
 | 
				
			||||||
 | 
					
 | 
				
			||||||
namespace msckf_vio {
 | 
					namespace msckf_vio {
 | 
				
			||||||
/*
 | 
					/*
 | 
				
			||||||
 * @brief MsckfVio Implements the algorithm in
 | 
					 * @brief MsckfVio Implements the algorithm in
 | 
				
			||||||
@@ -97,11 +110,27 @@ class MsckfVio {
 | 
				
			|||||||
    void imuCallback(const sensor_msgs::ImuConstPtr& msg);
 | 
					    void imuCallback(const sensor_msgs::ImuConstPtr& msg);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    /*
 | 
					    /*
 | 
				
			||||||
     * @brief featureCallback
 | 
					     * @brief truthCallback
 | 
				
			||||||
     *    Callback function for feature measurements.
 | 
					     *      Callback function for ground truth navigation information
 | 
				
			||||||
     * @param msg Stereo feature measurements.
 | 
					     * @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.
 | 
					     * @brief publish Publish the results of VIO.
 | 
				
			||||||
@@ -126,6 +155,26 @@ 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(
 | 
				
			||||||
@@ -137,8 +186,12 @@ 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.
 | 
				
			||||||
@@ -152,6 +205,20 @@ class MsckfVio {
 | 
				
			|||||||
    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,
 | 
				
			||||||
@@ -163,11 +230,32 @@ 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;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -179,6 +267,22 @@ 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;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -206,12 +310,20 @@ class MsckfVio {
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
    // Subscribers and publishers
 | 
					    // Subscribers and publishers
 | 
				
			||||||
    ros::Subscriber imu_sub;
 | 
					    ros::Subscriber imu_sub;
 | 
				
			||||||
    ros::Subscriber feature_sub;
 | 
					    ros::Subscriber truth_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;
 | 
				
			||||||
@@ -232,6 +344,9 @@ 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,9 +11,6 @@
 | 
				
			|||||||
#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 {
 | 
				
			||||||
@@ -21,10 +18,6 @@ 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,7 +8,8 @@
 | 
				
			|||||||
  <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"/>
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										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="false"/>
 | 
				
			||||||
 | 
					      <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"/>
 | 
					      <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>
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										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="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="~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,
 | 
					# 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,13 +3,12 @@
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
  <name>msckf_vio</name>
 | 
					  <name>msckf_vio</name>
 | 
				
			||||||
  <version>0.0.1</version>
 | 
					  <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>
 | 
					  <license>Penn Software License</license>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  <author email="sunke.polyu@gmail.com">Ke Sun</author>
 | 
					  <author email="raphael@maenle.net">Raphael Maenle</author>
 | 
				
			||||||
  <author email="kartikmohta@gmail.com">Kartik Mohta</author>
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
  <buildtool_depend>catkin</buildtool_depend>
 | 
					  <buildtool_depend>catkin</buildtool_depend>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -19,6 +18,7 @@
 | 
				
			|||||||
  <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>
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										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_
 | 
				
			||||||
							
								
								
									
										159
									
								
								src/image_handler.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										159
									
								
								src/image_handler.cpp
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,159 @@
 | 
				
			|||||||
 | 
					#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/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;
 | 
				
			||||||
@@ -43,49 +44,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)));
 | 
				
			||||||
@@ -123,27 +124,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;
 | 
				
			||||||
@@ -170,10 +171,6 @@ 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;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
@@ -204,13 +201,6 @@ 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...");
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -230,9 +220,7 @@ 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) {
 | 
				
			||||||
@@ -309,7 +297,6 @@ 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),
 | 
				
			||||||
@@ -317,7 +304,6 @@ 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),
 | 
				
			||||||
@@ -404,7 +390,6 @@ 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();
 | 
				
			||||||
@@ -435,7 +420,6 @@ 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;
 | 
				
			||||||
@@ -469,10 +453,8 @@ 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,
 | 
				
			||||||
@@ -483,25 +465,6 @@ 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.
 | 
				
			||||||
@@ -585,14 +548,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.
 | 
				
			||||||
@@ -646,7 +609,6 @@ 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) {
 | 
				
			||||||
@@ -654,31 +616,15 @@ 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;
 | 
				
			||||||
    undistortPoints(cam0_points, cam0_intrinsics, cam0_distortion_model,
 | 
					    image_handler::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_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.
 | 
					  // 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(),
 | 
				
			||||||
@@ -688,7 +634,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) {
 | 
				
			||||||
@@ -715,16 +661,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);
 | 
				
			||||||
  undistortPoints(
 | 
					  image_handler::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);
 | 
				
			||||||
  undistortPoints(
 | 
					  image_handler::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;
 | 
				
			||||||
@@ -751,8 +697,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) {
 | 
				
			||||||
@@ -772,7 +718,6 @@ 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);
 | 
				
			||||||
@@ -787,7 +732,6 @@ 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) {
 | 
				
			||||||
@@ -800,7 +744,6 @@ 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());
 | 
				
			||||||
@@ -828,7 +771,6 @@ 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 <
 | 
				
			||||||
@@ -850,7 +792,6 @@ 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(),
 | 
				
			||||||
@@ -900,73 +841,6 @@ 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.
 | 
				
			||||||
@@ -1018,7 +892,6 @@ 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) {
 | 
				
			||||||
@@ -1048,7 +921,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 (%i and %i) are used...",
 | 
					    ROS_ERROR("Sets of different size (%lu and %lu) 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]);
 | 
				
			||||||
@@ -1062,10 +935,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());
 | 
				
			||||||
  undistortPoints(
 | 
					  image_handler::undistortPoints(
 | 
				
			||||||
      pts1, intrinsics, distortion_model,
 | 
					      pts1, intrinsics, distortion_model,
 | 
				
			||||||
      distortion_coeffs, pts1_undistorted);
 | 
					      distortion_coeffs, pts1_undistorted);
 | 
				
			||||||
  undistortPoints(
 | 
					  image_handler::undistortPoints(
 | 
				
			||||||
      pts2, intrinsics, distortion_model,
 | 
					      pts2, intrinsics, distortion_model,
 | 
				
			||||||
      distortion_coeffs, pts2_undistorted);
 | 
					      distortion_coeffs, pts2_undistorted);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -1283,7 +1156,6 @@ 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;
 | 
				
			||||||
@@ -1303,12 +1175,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);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  undistortPoints(
 | 
					  image_handler::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);
 | 
				
			||||||
  undistortPoints(
 | 
					  image_handler::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());
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										1147
									
								
								src/msckf_vio.cpp
									
									
									
									
									
								
							
							
						
						
									
										1147
									
								
								src/msckf_vio.cpp
									
									
									
									
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							@@ -11,20 +11,6 @@
 | 
				
			|||||||
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