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

Revision history [back]

click to hide/show revision 1
initial version

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.