changed data handling in undistortion to work with euroc datset
This commit is contained in:
@ -541,14 +541,15 @@ void MsckfVio::manageMovingWindow(
|
||||
sensor_msgs::image_encodings::MONO8);
|
||||
cv_bridge::CvImageConstPtr cam1_img_ptr = cv_bridge::toCvShare(cam1_img,
|
||||
sensor_msgs::image_encodings::MONO8);
|
||||
|
||||
image_handler::undistortImage(cam0_img_ptr->image, cam0_img_ptr->image, cam0.distortion_model, cam0.intrinsics, cam0.distortion_coeffs);
|
||||
image_handler::undistortImage(cam1_img_ptr->image, cam1_img_ptr->image, cam1.distortion_model, cam1.intrinsics, cam1.distortion_coeffs);
|
||||
|
||||
|
||||
|
||||
cv::Mat newImage0;
|
||||
cv::Mat newImage1;
|
||||
image_handler::undistortImage(cam0_img_ptr->image, newImage0, cam0.distortion_model, cam0.intrinsics, cam0.distortion_coeffs);
|
||||
image_handler::undistortImage(cam1_img_ptr->image, newImage1, cam1.distortion_model, cam1.intrinsics, cam1.distortion_coeffs);
|
||||
|
||||
// save image information into moving window
|
||||
cam0.moving_window[state_server.imu_state.id].image = cam0_img_ptr->image.clone();
|
||||
cam1.moving_window[state_server.imu_state.id].image = cam1_img_ptr->image.clone();
|
||||
cam0.moving_window[state_server.imu_state.id].image = newImage0.clone();
|
||||
cam1.moving_window[state_server.imu_state.id].image = newImage1.clone();
|
||||
|
||||
cv::Mat xder;
|
||||
cv::Mat yder;
|
||||
|
Reference in New Issue
Block a user