ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

svo does not find enough features

asked 2016-02-18 05:31:28 -0500

codierknecht gravatar image

updated 2016-02-19 06:39:14 -0500

I use ROS to run the monocular visual odometry system Fast Semi-direct monocular visual odometry by the Robotics and Perception Group of the university of zurich. The system seems to run fine, but cannot detect enough features or recognizes the image noise as features, thus the tracking fails. SVO uses the FAST corner detector to find the features.

My camera is calibrated as pinhole camera using the camera_calibration package. I translated the result to the .yaml representation required by svo:

cam_model: Pinhole
cam_width: 644
cam_height: 484
cam_fx: 588.481298
cam_fy: 587.819899
cam_cx: 328.046456
cam_cy: 226.471844
cam_d0: -0.363501
cam_d1: 0.165011
cam_d2: 0.000571
cam_d3: -0.000577

When I start the svo_ros node it starts up fine. If the camera looks down on a checker board it mostly finds enough features and calculates disparity between the camera frames. Most of the time after the disparity between the initial keyframe and the current camera frame gets to big the second keyframe is initiated

Init: Selected second frame, triangulated initial map.

When this happens the node starts to reloacalize the camera, but does not find enough features. Even if it says that the relocalization was successful. Sometimes it relocalization is successful severel times, but not for long.

[ INFO] [1455793514.214189779]: Init: KLT 9.41041px average disparity.
[ INFO] [1455793514.223854484]: Init: KLT tracked 100 features
[ INFO] [1455793514.223905934]: Init: KLT 10.1109px average disparity.
[ INFO] [1455793514.224348786]: Init: Homography RANSAC 98 inliers.
[ INFO] [1455793514.224422911]: Init: Selected second frame, triangulated initial map.
[ WARN] [1455793514.462734378]: Tracking less than 50 features!
[ WARN] [1455793514.471598788]: Relocalizing frame
[ INFO] [1455793514.473348234]: Relocalization successful.
[ INFO] [1455793514.511837899]: Relocalization successful.
[ INFO] [1455793514.530851955]: Relocalization successful.
[ INFO] [1455793514.569877904]: Relocalization successful.
[ INFO] [1455793514.589040237]: Relocalization successful.
[ WARN] [1455793514.608333086]: Not enough matched features.

I tried to change the settings in the launch-file. I decreased the min_fts and init_min_disparity. This improved the results, but it doesn't either.

<param name="max_fts" value="300" type="int" />
<param name="min_fts" value="20" type="int" />
<param name="init_min_disparity" value="10.0" type="double" />

I also tried to pass the camera image to a node which blurs the image a little or to perform a histogram equalization, but there is no or only a little improvement.

Does someone know what the initial disparity is and why it has to be exceeded before the pose estimation begins (maybe for the depthestimation?) and why there are not enough features found after it?

Thanks in advance.

edit retag flag offensive close merge delete

Comments

when i use logitech C310 usb camera,it also always print "No reference keyframe" ," Relocalizing frame".Did you have fixed this problem?

jxl gravatar image jxl  ( 2016-11-28 06:10:03 -0500 )edit

Hi, sadly I was not able to solve the problem. In the next days I'll try to use the camera from the original project. Maybe I can figure out some differences and understand why our usb webcams doesn't work. I am going to tell you my results.

codierknecht gravatar image codierknecht  ( 2016-11-28 08:30:30 -0500 )edit

Thanks very much :)

jxl gravatar image jxl  ( 2016-11-30 02:27:24 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2016-07-26 16:38:59 -0500

kev1nnsays gravatar image

SVO is configured to only select new features when the computed position of the camera moves past a certain displacement from the last Key Frame. Look in frame_handeler_mono.cpp:

bool FrameHandlerMono::needNewKf(double scene_depth_mean)
{
  for(auto it=overlap_kfs_.begin(), ite=overlap_kfs_.end(); it!=ite; ++it)
  {
    Vector3d relpos = new_frame_->w2f(it->first->pos());
    const size_t repr_n_new_references = reprojector_.n_matches_;
    if(fabs(relpos.x())/scene_depth_mean < Config::kfSelectMinDist() &&
   fabs(relpos.y())/scene_depth_mean < Config::kfSelectMinDist()*0.8 &&
   fabs(relpos.z())/scene_depth_mean < Config::kfSelectMinDist()*1.3)
      return false;
  }
  return true;
}

You'll see that new references are not selected until the relative position between the robot and the last key frame is greater than kfSelectMinDist. You can adjust the coefficients to optimize for forward movement:

fabs(relpos.x())/scene_depth_mean < Config::kfSelectMinDist() 1.3 &&
   fabs(relpos.y())/scene_depth_mean < Config::kfSelectMinDist()*0.8 &&
   fabs(relpos.z())/scene_depth_mean < Config::kfSelectMinDist()

However, this still doesn't handle rotation at all. If your robot rotates in place, it's relative position to the last key frame is nearly zero. I'm still trying to figure out how to structure the "if" statement to grab new points when the number of matching points dips below a threshold.

edit flag offensive delete link more

Comments

Hi, sorry for late answer^^ I was working on other projects in the meantime. I already tried to fit the parameters to my scenario and even tried to "improof" the image for better detection, but nothing worked.

codierknecht gravatar image codierknecht  ( 2016-11-28 08:33:52 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-02-18 05:31:28 -0500

Seen: 1,666 times

Last updated: Jul 26 '16