added image rescaling factor
This commit is contained in:
parent
0ef71b9220
commit
e94d4a06b5
@ -286,7 +286,8 @@ class MsckfVio {
|
||||
|
||||
// Patch size for Photometry
|
||||
int N;
|
||||
|
||||
// Image rescale
|
||||
int SCALE;
|
||||
// Chi squared test table.
|
||||
static std::map<int, double> chi_squared_test_table;
|
||||
|
||||
|
@ -27,9 +27,9 @@
|
||||
<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"/>
|
||||
<remap from="~imu" to="/imu02"/>
|
||||
<remap from="~cam0_image" to="/cam0/image_raw2"/>
|
||||
<remap from="~cam1_image" to="/cam1/image_raw2"/>
|
||||
|
||||
|
||||
</node>
|
||||
|
@ -19,14 +19,15 @@
|
||||
|
||||
|
||||
<!-- Filter Flag, 0 = msckf, 1 = photometric, 2 = two -->
|
||||
<param name="FILTER" value="2"/>
|
||||
<param name="FILTER" value="1"/>
|
||||
|
||||
<!-- Debugging Flaggs -->
|
||||
<param name="StreamPause" value="true"/>
|
||||
<param name="PrintImages" value="false"/>
|
||||
<param name="PrintImages" value="true"/>
|
||||
<param name="GroundTruth" value="false"/>
|
||||
|
||||
<param name="patch_size_n" value="3"/>
|
||||
<param name="patch_size_n" value="5"/>
|
||||
<param name="image_scale" value ="1"/>
|
||||
|
||||
<!-- Calibration parameters -->
|
||||
<rosparam command="load" file="$(arg calibration_file)"/>
|
||||
|
@ -25,7 +25,9 @@
|
||||
<param name="PrintImages" value="false"/>
|
||||
<param name="GroundTruth" value="false"/>
|
||||
|
||||
<param name="patch_size_n" value="5"/>
|
||||
<param name="patch_size_n" value="3"/>
|
||||
<param name="image_scale" value ="1"/>
|
||||
|
||||
<!-- Calibration parameters -->
|
||||
<rosparam command="load" file="$(arg calibration_file)"/>
|
||||
|
||||
|
@ -137,6 +137,8 @@ bool MsckfVio::loadParameters() {
|
||||
// Get the photometric patch size
|
||||
nh.param<int>("patch_size_n",
|
||||
N, 3);
|
||||
// Get rescaling factor for image
|
||||
nh.param<int>("image_scale", SCALE, 1);
|
||||
|
||||
// get camera information (used for back projection)
|
||||
nh.param<string>("cam0/distortion_model",
|
||||
@ -425,10 +427,10 @@ void MsckfVio::imageCallback(
|
||||
// the origin.
|
||||
if (is_first_img) {
|
||||
is_first_img = false;
|
||||
cam0.intrinsics *=0.5;
|
||||
cam1.intrinsics *=0.5;
|
||||
cam0.resolution *=0.5;
|
||||
cam1.resolution *=0.5;
|
||||
//cam0.intrinsics *=SCALE;
|
||||
//cam1.intrinsics *=SCALE;
|
||||
//cam0.resolution *=SCALE;
|
||||
//cam1.resolution *=SCALE;
|
||||
state_server.imu_state.time = feature_msg->header.stamp.toSec();
|
||||
}
|
||||
static double max_processing_time = 0.0;
|
||||
@ -550,22 +552,23 @@ void MsckfVio::manageMovingWindow(
|
||||
|
||||
cv::Mat new_cam0;
|
||||
cv::Mat new_cam1;
|
||||
cam0.intrinsics *=2;
|
||||
cam1.intrinsics *=2;
|
||||
cam0.resolution *=2;
|
||||
cam1.resolution *=2;
|
||||
//cam0.intrinsics *=float(1./SCALE);
|
||||
//cam1.intrinsics *=float(1./SCALE);
|
||||
//cam0.resolution *=float(1./SCALE);
|
||||
//cam1.resolution *=float(1./SCALE);
|
||||
image_handler::undistortImage(cam0_img_ptr->image, new_cam0, cam0.distortion_model, cam0.intrinsics, cam0.distortion_coeffs);
|
||||
image_handler::undistortImage(cam1_img_ptr->image, new_cam1, cam1.distortion_model, cam1.intrinsics, cam1.distortion_coeffs);
|
||||
cam0.intrinsics *=0.5;
|
||||
cam1.intrinsics *=0.5;
|
||||
cam0.resolution *=0.5;
|
||||
cam1.resolution *=0.5;
|
||||
//cam0.intrinsics *=SCALE;
|
||||
//cam1.intrinsics *=SCALE;
|
||||
//cam0.resolution *=SCALE;
|
||||
//cam1.resolution *=SCALE;
|
||||
//resize
|
||||
|
||||
int SCALE = 1;yy
|
||||
cv::Mat new_cam02;
|
||||
cv::Mat new_cam12;
|
||||
cv::resize(new_cam0, new_cam02, cv::Size(), 0.5, 0.5);
|
||||
cv::resize(new_cam1, new_cam12, cv::Size(), 0.5, 0.5);
|
||||
cv::resize(new_cam0, new_cam02, cv::Size(), SCALE, SCALE);
|
||||
cv::resize(new_cam1, new_cam12, cv::Size(), SCALE, SCALE);
|
||||
|
||||
// save image information into moving window
|
||||
cam0.moving_window[state_server.imu_state.id].image = new_cam02.clone();
|
||||
|
Loading…
Reference in New Issue
Block a user