对当前帧进行地图点重投影和特征对齐

  1. // map reprojection & feature alignment
  2. SVO_START_TIMER("reproject");
  3. reprojector_.reprojectMap(new_frame_, overlap_kfs_);
  4. SVO_STOP_TIMER("reproject");

在processframe函数中在进行初始的稀疏图像对齐之后,进一步进行地图投影和特征对齐,对新一帧图像添加特征点,由reprojectMap接口进入

  1. Reprojector reprojector_; //把其它关键帧中的点投影到当前帧中
  2.  
  3. FramePtr new_frame_; // 当前帧
  1. vector< pair<FramePtr,size_t> > overlap_kfs_; // 具有重叠视野的所有关键帧。 配对数字指明观察到的公共地图点数。
  1. void Reprojector::reprojectMap(
  2. FramePtr frame,
  3. std::vector< std::pair<FramePtr,std::size_t> >& overlap_kfs)
  4. {
  5. resetReprojGrid();
  1. resetReprojGrid(); // 重置函数
  1. // Identify those Keyframes which share a common field of view.
  2. SVO_START_TIMER("reproject_kfs");
  3. list< pair<FramePtr,double> > close_kfs;
  4. map_.getCloseKeyframes(frame, close_kfs);
  1.  

void Map::getCloseKeyframes(
const FramePtr& frame,
std::list< std::pair<FramePtr,double> >& close_kfs);

const FramePtr& frame;    //当前图像帧

std::list< std::pair<FramePtr,double> >& close_kfs  ;///存储和当前帧接近的关键帧指针以及它们之间的距离。

  1. 根据它们的接近程度对KF进行重叠排序(列表中的第二个值)
  1. close_kfs.sort(boost::bind(&std::pair<FramePtr, double>::second, _1) <
  2. boost::bind(&std::pair<FramePtr, double>::second, _2));
  1.  

重新投影具有重叠的最近N kfs的所有地图特征。

  1. size_t n_kfs = ;
  2. overlap_kfs.reserve(options_.max_n_kfs);
  3. for(auto it_frame=close_kfs.begin(), ite_frame=close_kfs.end();
  4. it_frame!=ite_frame && n_kfs<options_.max_n_kfs; ++it_frame, ++n_kfs)
  5. {
  6. FramePtr ref_frame = it_frame->first;
  7. // add the current frame to the (output) list of keyframes with overlap
  8. // initialize the counter of candidates from this frame (2nd element in pair) to zero
  9. overlap_kfs.push_back(pair<FramePtr,size_t>(ref_frame,));
  10. // Consider for candidate each mappoint in the ref KF that the current (input) KF observes
  11. // We only store in which grid cell the points fall.
  12. // Add each corresponding valid new Candidate to its cell in the grid.
  13. int num_pt_success = setKfCandidates( frame, ref_frame->pt_fts_ );
  14. overlap_kfs.back().second += num_pt_success;
  15. // Add each line segment in the ref KF that the current (input) KF observes
  16. int num_seg_success = setKfCandidates( frame, ref_frame->seg_fts_ );
  17. overlap_kfs.back().second += num_seg_success;
  18. }
  19. SVO_STOP_TIMER("reproject_kfs");
  1. 考虑当前(输入)KF观察到的参考KF中的每个mappoint的候选者

我们只存储点落在哪个网格单元格中。

将每个对应的有效新Candidate添加到网格中的单元格中。

  1. template<class FeatureT>
  2. int Reprojector::setKfCandidates(FramePtr frame, list<FeatureT*> fts)
  3. {
  4. int candidate_counter = ;
  5. for(auto it=fts.begin(), ite_ftr=fts.end(); it!=ite_ftr; ++it)
  6. {
  7. // check if the feature has a 3D object assigned
  8. if((*it)->feat3D == NULL)
  9. continue;
  10. // make sure we project a point only once
  11. if((*it)->feat3D->last_projected_kf_id_ == frame->id_)
  12. continue;
  13. (*it)->feat3D->last_projected_kf_id_ = frame->id_;
  14. if(reproject(frame, (*it)->feat3D))
  15. // increment the number of candidates taken successfully
  16. candidate_counter++;
  17. }
  18. return candidate_counter;
  19. }

int Reprojector::setKfCandidates(FramePtr frame, list<FeatureT*> fts)

把地图点和投影到当前帧中的像素点的匹配对存储到  grid_.cells 中

  1.  
  1. bool Reprojector::reproject(FramePtr frame, Point* point)
  2. {
  3. // get position in current frame image of the world 3D point
  4. Vector2d cur_px(frame->w2c(point->pos_));
  5. if(frame->cam_->isInFrame(cur_px.cast<int>(), )) // 8px is the patch size in the matcher
  6. {
  7. // get linear index (wrt row-wise vectorized grid matrix)
  8. // of the image grid cell in which the point px lies
  9. const int k = static_cast<int>(cur_px[]/grid_.cell_size)*grid_.grid_n_cols
  10. + static_cast<int>(cur_px[]/grid_.cell_size);
  11. grid_.cells.at(k)->push_back(PointCandidate(point, cur_px));
  12. return true;
  13. }
  14. return false;
  15. }
  1.  

数据类型的定义

  1. struct PointCandidate {
  2. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  3. Point* pt; //!< 3D point.
  4. Vector2d px; //!< projected 2D pixel location.
  5. PointCandidate(Point* pt, Vector2d& px) : pt(pt), px(px) {}
  6. };
  1. // A cell is just a list of Reprojector::Candidate
  2. typedef std::list<PointCandidate, aligned_allocator<PointCandidate> > Cell;
  3. typedef std::vector<Cell*> CandidateGrid;
  4.  
  5. struct LineCandidate {
  6. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  7. LineSeg* ls; //!< 3D point.
  8. Vector2d spx;
  9. Vector2d epx;
  10. LineCandidate(LineSeg* ls, Vector2d& spx, Vector2d& epx) : ls(ls), spx(spx), epx(epx) {}
  11. };
  1. /// The candidate segments are collected in a single list for the whole image.
  2. /// There is no clear heuristic about how to discretize the image space for the segment case.
  3. typedef std::list<LineCandidate, aligned_allocator<LineCandidate> > LineCandidates;
  4. typedef std::vector<LineCandidates*> LineCandidateGrid;
  5.  
  6. /// The grid stores a set of candidate matches. For every grid cell we try to find one match.
  7. struct Grid
  8. {
  9. CandidateGrid cells;
  10. vector<int> cell_order;
  11. int cell_size;
  12. int grid_n_cols;
  13. int grid_n_rows;
  14. };
  15.  
  16. struct GridLs
  17. {
  18. LineCandidateGrid cells;
  19. vector<int> cell_order;
  20. int cell_size;
  21. int grid_n_cols;
  22. int grid_n_rows;
  23. };
  24.  
  25. Grid grid_;
  26. GridLs gridls_;
  27. Matcher matcher_;
  28. Map& map_;

现在投影所有地图坐标

点坐标

  1. // Now project all map candidates
  2. // (candidates in the map are created from converged seeds)
  3. SVO_START_TIMER("reproject_candidates");
  4. // Point candidates
  5. // (same logic as above to populate the cell grid but taking candidate points from the map object)
  6. setMapCandidates(frame, map_.point_candidates_);

线坐标

  1. // Segment candidates
  2. setMapCandidates(frame, map_.segment_candidates_);
  3. SVO_STOP_TIMER("reproject_candidates");

Map&    map_;  //地图类

MapPointCandidates point_candidates_;   //  收敛的3D点的容器,尚未分配给两个关键帧。

MapSegmentCandidates segment_candidates_;    /////尚未分配给两个关键帧的融合3D点的容器。

  1. class MapPointCandidates
  2. {
  3. public:
  4. typedef pair<Point*, PointFeat*> PointCandidate;
  5. typedef list<PointCandidate> PointCandidateList;
  6.  
  7. /// The depth-filter is running in a parallel thread and fills the canidate list.
  8. /// This mutex controls concurrent access to point_candidates.
  9. boost::mutex mut_;
  10.  
  11. /// Candidate points are created from converged seeds.
  12. /// Until the next keyframe, these points can be used for reprojection and pose optimization.
  13. PointCandidateList candidates_;
  14. list< Point* > trash_points_;
  15.  
  16. MapPointCandidates();
  17. ~MapPointCandidates();
  18.  
  19. /// Add a candidate point.
  20. void newCandidatePoint(Point* point, double depth_sigma2);
  21.  
  22. /// Adds the feature to the frame and deletes candidate from list.
  23. void addCandidatePointToFrame(FramePtr frame);
  24.  
  25. /// Remove a candidate point from the list of candidates.
  26. bool deleteCandidatePoint(Point* point);
  27.  
  28. /// Remove all candidates that belong to a frame.
  29. void removeFrameCandidates(FramePtr frame);
  30.  
  31. /// Reset the candidate list, remove and delete all points.
  32. void reset();
  33.  
  34. void deleteCandidate(PointCandidate& c);
  35.  
  36. void emptyTrash();
  37. };
  1. void MapPointCandidates::deleteCandidate(PointCandidate& c)
  2. {
  3. // camera-rig: another frame might still be pointing to the candidate point
  4. // therefore, we can't delete it right now.
  5. delete c.second; c.second=NULL;
  6. c.first->type_ = Point::TYPE_DELETED;
  7. trash_points_.push_back(c.first);
  8. }
  1.  
  1. template<class MapCandidatesT>
  2. void Reprojector::setMapCandidates(FramePtr frame, MapCandidatesT &map_candidates)
  3. {
  4. boost::unique_lock<boost::mutex> lock(map_candidates.mut_); // the mutex will be unlocked when out of scope
  5. auto it=map_candidates.candidates_.begin();
  6. while(it!=map_candidates.candidates_.end())
  7. {
  8. if(!reproject(frame, it->first))
  9. {
  10. // if the reprojection of the map candidate point failed,
  11. // increment the counter of failed reprojections (assess the point quality)
  12. it->first->n_failed_reproj_ += ;
  13. if(it->first->n_failed_reproj_ > )
  14. {
  15. // if the reprojection failed too many times, remove the map candidate point
  16. map_candidates.deleteCandidate(*it);
  17. it = map_candidates.candidates_.erase(it);
  18. continue;
  19. }
  20. }
  21. ++it;
  22. } // end-while-loop
  23. }
  1.  

现在我们浏览每个网格单元并选择一个匹配点。最后,我们每个细胞最多应该有一个重新投射点。


  1. SVO_START_TIMER("feature_align");
  2. for(size_t i=; i<grid_.cells.size(); ++i)
  3. {
  4. // we prefer good quality points over unkown quality (more likely to match)
  5. // and unknown quality over candidates (position not optimized)
  6. // we use the random cell order to visit cells uniformly on the grid
  7. if(refineBestCandidate(*grid_.cells.at(grid_.cell_order[i]), frame))
  8. ++n_matches_;
  9. if(n_matches_ > (size_t) Config::maxFts())
  10. break; // the random visit order of cells assures uniform distribution
  11. // of the features even if we break early (maxFts reached soon)
  12. }

我们更喜欢质量好的点而不是未知质量(更可能匹配)和未知质量而不是候选者(位置未优化)

我们使用随机单元格顺序在网格上统一访问单元格

  1.  
  1. bool Reprojector::refineBestCandidate(Cell& cell, FramePtr frame)
  2. {
  3. // sort the candidates inside the cell according to their quality
  4. cell.sort(boost::bind(&Reprojector::pointQualityComparator, _1, _2));
  5. Cell::iterator it=cell.begin();
  6. // in principle, iterate through the whole list of features in the cell
  7. // in reality, there is maximum one point per cell, so the loop returns if successful
  8. while(it!=cell.end())
  9. {
  10. ++n_trials_;
  11. // Try to refine the point feature in frame from current initial estimate
  12. bool success = refine( it->pt, it->px, frame );
  13. // Failed or not, this candidate was finally being erased in original code
  14. it = cell.erase(it); // it takes next position in the list as output of .erase
  15. if(success)
  16. // Maximum one point per cell.
  17. return true;
  18. }
  19. return false;
  20. }
  1.  

尝试从当前初始估计中细化帧中的点要素

  1. bool Reprojector::refine(Point* pt, Vector2d& px_est, FramePtr frame)
  2. {
  3. if(pt->type_ == Point::TYPE_DELETED)
  4. return false;
  5.  
  6. bool found_match = true;
  7. if(options_.find_match_direct)
  8. // refine px position in the candidate by directly applying subpix refinement
  9. // internally, it is optimizing photometric error
  10. // of the candidate px patch wrt the closest-view reference feature patch
  11. found_match = matcher_.findMatchDirect(*pt, *frame, px_est);
  12. // TODO: What happens if options_.find_match_direct is false??? Shouldn't findEpipolarMatchDirect be here?
  13.  
  14. // apply quality logic
  15. {
  16. if(!found_match)
  17. {
  18. // if there is no match found for this point, decrease quality
  19. pt->n_failed_reproj_++;
  20. // consider removing the point from map depending on point type and quality
  21. if(pt->type_ == Point::TYPE_UNKNOWN && pt->n_failed_reproj_ > )
  22. map_.safeDeletePoint(pt);
  23. if(pt->type_ == Point::TYPE_CANDIDATE && pt->n_failed_reproj_ > )
  24. map_.point_candidates_.deleteCandidatePoint(pt);
  25. return false;
  26. }
  27. // if there is successful match found for this point, increase quality
  28. pt->n_succeeded_reproj_++;
  29. if(pt->type_ == Point::TYPE_UNKNOWN && pt->n_succeeded_reproj_ > )
  30. pt->type_ = Point::TYPE_GOOD;
  31. }
  32.  
  33. // create new point feature for this frame with the refined (aligned) candidate position in this image
  34. PointFeat* new_feature = new PointFeat(frame.get(), px_est, matcher_.search_level_);
  35. frame->addFeature(new_feature);
  36.  
  37. // Here we add a reference in the feature to the 3D point, the other way
  38. // round is only done if this frame is selected as keyframe.
  39. // TODO: why not give it directly to the constructor PointFeat(frame.get(), pt, it->px, matcher_.serach_level_)
  40. new_feature->feat3D = pt;
  41.  
  42. PointFeat* pt_ftr = static_cast<PointFeat*>( matcher_.ref_ftr_ );
  43. if(pt_ftr != NULL)
  44. {
  45. if(pt_ftr->type == PointFeat::EDGELET)
  46. {
  47. new_feature->type = PointFeat::EDGELET;
  48. new_feature->grad = matcher_.A_cur_ref_*pt_ftr->grad;
  49. new_feature->grad.normalize();
  50. }
  51. }
  52.  
  53. // If the keyframe is selected and we reproject the rest, we don't have to
  54. // check this point anymore.
  55. // it = cell.erase(it);
  56.  
  57. // Maximum one point per cell.
  58. return true;
  59. }

通过直接应用子像素细化来细化候选者中的px位置

在内部,它正在优化最近视图参考特征补丁的候选px补丁的光度误差

  1. bool Matcher::findMatchDirect(
  2. const Point& pt,
  3. const Frame& cur_frame,
  4. Vector2d& px_cur)
  5. {
  6. // get reference feature in closest view (frame)
  7. if(!pt.getCloseViewObs(cur_frame.pos(), ref_ftr_))
  8. return false;
  9.  
  10. if(!ref_ftr_->frame->cam_->isInFrame(
  11. ref_ftr_->px.cast<int>()/(<<ref_ftr_->level), halfpatch_size_+, ref_ftr_->level))
  12. return false;
  13.  
  14. // warp affine
  15. warp::getWarpMatrixAffine(
  16. *ref_ftr_->frame->cam_, *cur_frame.cam_, ref_ftr_->px, ref_ftr_->f,
  17. (ref_ftr_->frame->pos() - pt.pos_).norm(),
  18. cur_frame.T_f_w_ * ref_ftr_->frame->T_f_w_.inverse(), ref_ftr_->level, A_cur_ref_);
  19. search_level_ = warp::getBestSearchLevel(A_cur_ref_, Config::nPyrLevels()-);
  20. // is img of ref_frame fully available at any time? that means keeping stored previous images, for how long?
  21. warp::warpAffine(A_cur_ref_, ref_ftr_->frame->img_pyr_[ref_ftr_->level], ref_ftr_->px,
  22. ref_ftr_->level, search_level_, halfpatch_size_+, patch_with_border_);
  23. // patch_with_border_ stores the square patch (of pixel intensities) around the reference feature
  24. // once the affine transformation is applied to the original reference image
  25. // the border is necessary for gradient operations (intensities at the border must be precomputed by interpolation too!)
  26. createPatchFromPatchWithBorder();
  27.  
  28. // px_cur should be set
  29. Vector2d px_scaled(px_cur/(<<search_level_));
  30.  
  31. bool success = false;
  32. PointFeat* pt_ftr = static_cast<PointFeat*>(ref_ftr_);
  33. if(pt_ftr->type == PointFeat::EDGELET)
  34. {
  35. Vector2d dir_cur(A_cur_ref_*pt_ftr->grad);
  36. dir_cur.normalize();
  37. success = feature_alignment::align1D(
  38. cur_frame.img_pyr_[search_level_], dir_cur.cast<float>(),
  39. patch_with_border_, patch_, options_.align_max_iter, px_scaled, h_inv_);
  40. }
  41. else
  42. {
  43. success = feature_alignment::align2D(
  44. cur_frame.img_pyr_[search_level_], patch_with_border_, patch_,
  45. options_.align_max_iter, px_scaled);
  46. }
  47. px_cur = px_scaled * (<<search_level_);
  48. return success;
  49. }

特征细化

  1. bool align2D(
  2. const cv::Mat& cur_img,
  3. uint8_t* ref_patch_with_border,
  4. uint8_t* ref_patch,
  5. const int n_iter,
  6. Vector2d& cur_px_estimate,
  7. bool no_simd)
  8. {
  9. #ifdef __ARM_NEON__
  10. if(!no_simd)
  11. return align2D_NEON(cur_img, ref_patch_with_border, ref_patch, n_iter, cur_px_estimate);
  12. #endif
  13.  
  14. const int patch_size_ = ;
  15. Patch patch( patch_size_, cur_img );
  16. bool converged=false;
  17.  
  18. /* Precomputation step: derivatives in reference patch */
  19. // compute derivative of template and prepare inverse compositional
  20. float __attribute__((__aligned__())) ref_patch_dx[patch.area];
  21. float __attribute__((__aligned__())) ref_patch_dy[patch.area];
  22. Matrix3f H; H.setZero();
  23.  
  24. // compute gradient and hessian
  25. const int ref_step = patch_size_+; // assumes ref_patch_with_border comes from a specific Mat object with certain size!!! Bad way to do it?
  26. float* it_dx = ref_patch_dx;
  27. float* it_dy = ref_patch_dy;
  28. for(int y=; y<patch_size_; ++y)
  29. {
  30. uint8_t* it = ref_patch_with_border + (y+)*ref_step + ;
  31. for(int x=; x<patch_size_; ++x, ++it, ++it_dx, ++it_dy)
  32. {
  33. Vector3f J;
  34. J[] = 0.5 * (it[] - it[-]);
  35. J[] = 0.5 * (it[ref_step] - it[-ref_step]);
  36. J[] = ;
  37. *it_dx = J[];
  38. *it_dy = J[];
  39. H += J*J.transpose();
  40. }
  41. }
  42. Matrix3f Hinv = H.inverse();
  43. float mean_diff = ;
  44.  
  45. /* Iterative loop: residues and updates with patch in current image */
  46. // Compute pixel location in new image:
  47. float u = cur_px_estimate.x();
  48. float v = cur_px_estimate.y();
  49.  
  50. // termination condition
  51. const float min_update_squared = 0.03*0.03;
  52. const int cur_step = cur_img.step.p[];
  53. // float chi2 = 0;
  54. Vector3f update; update.setZero();
  55. for(int iter = ; iter<n_iter; ++iter)
  56. {
  57. // TODO very rarely this can happen, maybe H is singular? should not be at corner.. check
  58. // if(isnan(cur_px_estimate[0]) || isnan(cur_px_estimate[1]))
  59. // return false;
  60.  
  61. // set patch position for current feature location
  62. patch.setPosition( cur_px_estimate );
  63. // abort the optimization if the patch does not fully lie within the image
  64. if(!patch.isInFrame(patch.halfsize))
  65. break;
  66. // compute interpolation weights
  67. patch.computeInterpWeights();
  68.  
  69. // set ROI in the current image to traverse
  70. patch.setRoi();
  71. // loop through search_patch, interpolate
  72. uint8_t* it_ref = ref_patch;
  73. float* it_ref_dx = ref_patch_dx;
  74. float* it_ref_dy = ref_patch_dy;
  75. uint8_t* ptr; // pointer that will point to memory locations of the ROI (same memory as for the original full cur_img)
  76. // float new_chi2 = 0.0;
  77. Vector3f Jres; Jres.setZero();
  78. for(int y=; y<patch.size; ++y)
  79. {
  80. // get the pointer to first element in row y of the patch ROI
  81. ptr = patch.roi.ptr(y);
  82. for(int x=; x<patch.size; ++x, ++ptr, ++it_ref, ++it_ref_dx, ++it_ref_dy)
  83. {
  84. float search_pixel = patch.wTL*ptr[] + patch.wTR*ptr[] + patch.wBL*ptr[cur_step] + patch.wBR*ptr[cur_step+];
  85. float res = search_pixel - *it_ref + mean_diff;
  86. Jres[] -= res*(*it_ref_dx);
  87. Jres[] -= res*(*it_ref_dy);
  88. Jres[] -= res;
  89. // new_chi2 += res*res;
  90. }
  91. }
  92.  
  93. /*
  94. if(iter > 0 && new_chi2 > chi2)
  95. {
  96. #if SUBPIX_VERBOSE
  97. cout << "error increased." << endl;
  98. #endif
  99. u -= update[0];
  100. v -= update[1];
  101. break;
  102. }
  103. chi2 = new_chi2;
  104. */
  105. update = Hinv * Jres;
  106. u += update[];
  107. v += update[];
  108. cur_px_estimate = Vector2d(u,v);
  109. mean_diff += update[];
  110.  
  111. #if SUBPIX_VERBOSE
  112. cout << "Iter " << iter << ":"
  113. << "\t u=" << u << ", v=" << v
  114. << "\t update = " << update[] << ", " << update[]
  115. // << "\t new chi2 = " << new_chi2 << endl;
  116. #endif
  117.  
  118. if(update[]*update[]+update[]*update[] < min_update_squared)
  119. {
  120. #if SUBPIX_VERBOSE
  121. cout << "converged." << endl;
  122. #endif
  123. converged=true;
  124. break;
  125. }
  126. }
  127.  
  128. cur_px_estimate << u, v;
  129. return converged;
  130. }

//为当前创建新的点特征,并在此图像中使用精确(对齐)的位置坐标

  1. PointFeat* new_feature = new PointFeat(frame.get(), px_est, matcher_.search_level_);
  2. frame->addFeature(new_feature);

在这里,我们将特征中的引用添加到3D点,只有在选择此帧作为关键帧时才进行另一种方式。

  1.  
  1. if(pt_ftr != NULL)
  2. {
  3. if(pt_ftr->type == PointFeat::EDGELET)
  4. {
  5. new_feature->type = PointFeat::EDGELET;
  6. new_feature->grad = matcher_.A_cur_ref_*pt_ftr->grad;
  7. new_feature->grad.normalize();
  8. }
  9. }
  1.  

尝试优化每个细分线段坐标

即使我们提前破坏,细胞的随机访问顺序也能确保特征的均匀分布(maxFts即将到达)

  1. for(size_t i=; i<gridls_.cells.size(); ++i)
  2. {
  3. if(refineBestCandidate(*gridls_.cells.at(gridls_.cell_order[i]), frame))
  4. ++n_ls_matches_;
  5. if(n_ls_matches_ > (size_t) Config::maxFtsSegs())
  6. break; // the random visit order of cells assures uniform distribution
  7. // of the features even if we break early (maxFts reached soon)
  8. }
  9. /*for(auto it = lines_.begin(), ite = lines_.end(); it!=ite; ++it)
  10. {
  11. if(refine(it->ls,it->spx,it->epx,frame))
  12. ++n_ls_matches_;
  13. if(n_ls_matches_ > (size_t) Config::maxFtsSegs())
  14. break;
  15. }*/
  16. SVO_STOP_TIMER("feature_align");

特征细化结束


  1.  
  1.  

PL-SVO公式推导及代码解析:地图点重投影和特征对齐的更多相关文章

  1. PL-SVO公式推导及代码解析:位姿优化

    通过跳过极线约束单独优化图像中每个特征的位置后,必须通过最小化3D特征与图像中相应的2D特征位置之间的重投影误差来进一步细化(3)中获得的相机姿态( 见图5).为此,我们考虑在世界坐标系中3D特征和相 ...

  2. loam详细代码解析与公式推导

    loam详细代码解析与公式推导(基础理论知识) 一.基础坐标变换 loam中欧拉角解算都采用R P Y 的解算方式,即先左乘R, 再左乘P, 最后左乘Y,用矩阵表示为: R = Ry * Rp * R ...

  3. 机器学习(公式推导与代码实现)--sklearn机器学习库

    一.scikit-learn概述 1.sklearn模型   sklearn全称是scikit-learn,它是一个基于Python的机器学习类库,主要建立在NumPy.Pandas.SciPy和Ma ...

  4. VBA常用代码解析

    031 删除工作表中的空行 如果需要删除工作表中所有的空行,可以使用下面的代码. Sub DelBlankRow() DimrRow As Long DimLRow As Long Dimi As L ...

  5. [nRF51822] 12、基础实验代码解析大全 · 实验19 - PWM

    一.PWM概述: PWM(Pulse Width Modulation):脉冲宽度调制技术,通过对一系列脉冲的宽度进行调制,来等效地获得所需要波形. PWM 的几个基本概念: 1) 占空比:占空比是指 ...

  6. [nRF51822] 11、基础实验代码解析大全 · 实验16 - 内部FLASH读写

     一.实验内容: 通过串口发送单个字符到NRF51822,NRF51822 接收到字符后将其写入到FLASH 的最后一页,之后将其读出并通过串口打印出数据. 二.nRF51822芯片内部flash知识 ...

  7. [nRF51822] 10、基础实验代码解析大全 · 实验15 - RTC

    一.实验内容: 配置NRF51822 的RTC0 的TICK 频率为8Hz,COMPARE0 匹配事件触发周期为3 秒,并使能了TICK 和COMPARE0 中断. TICK 中断中驱动指示灯D1 翻 ...

  8. [nRF51822] 9、基础实验代码解析大全 · 实验12 - ADC

    一.本实验ADC 配置 分辨率:10 位. 输入通道:5,即使用输入通道AIN5 检测电位器的电压. ADC 基准电压:1.2V. 二.NRF51822 ADC 管脚分布 NRF51822 的ADC ...

  9. java集合框架之java HashMap代码解析

     java集合框架之java HashMap代码解析 文章Java集合框架综述后,具体集合类的代码,首先以既熟悉又陌生的HashMap开始. 源自http://www.codeceo.com/arti ...

随机推荐

  1. Django-3-Template模板

    模板是html文档+Django逻辑语句的组合. 一.变量和标签 变量通过{{ }}来表示,两个大括号中间是变量名. 标签通过{% %}来表示,就是Python中的函数和方法. 常用标签: {% fo ...

  2. 主机服务绑定IP

    在用 netstat -na  查看当前主机提供的服务,例如显示如下结果: tcp        0      0 127.0.0.1:9000              0.0.0.0:*      ...

  3. 【转】【Linux】Swap与Memory

    背景介绍 Memory指机器物理内存,读写速度低于CPU一个量级,但是高于磁盘不止一个量级.所以,程序和数据如果在内存的话,会有非常快的读写速度.但是,内存的造价是要高于磁盘的,且内存的断电丢失数据也 ...

  4. 【原创】运维基础之Docker(7)关于docker latest tag

    Docker images have a tag named latest which doesn’t work as you expect.Latest is just a tag with a s ...

  5. Ubuntu 18.04LTS 更新镜像配置

    清华大学开源镜像站:https://mirrors.tuna.tsinghua.edu.cn/help/ubuntu/ Ubuntu 的软件源配置文件是 /etc/apt/sources.list.将 ...

  6. TensorFlow的Bazel构建文件结构

    目录 说明 分析 全局设定文件:$TF_ROOT/WORKSPACE 外部依赖项入口:tensorflow/workspace.bzl 看看有多少package? 本来是想理解一下TF源码编译过程的, ...

  7. 必须知道的Linux内核常识详解

    一.内核功能.内核发行版 1.到底什么是操作系统 (1)linux.windows.android.ucos就是操作系统: (2)操作系统本质上是一个程序,由很多个源文件构成,需要编译连接成操作系统程 ...

  8. Codeforces 755F PolandBall and Gifts bitset + 二进制优化多重背包

    PolandBall and Gifts 转换成置换群后, 对于最大值我们很好处理. 对于最小值, 只跟若干个圈能否刚好组能 k 有关. 最直观的想法就是bitset优化背包, 直接搞肯定T掉. 我们 ...

  9. java代码获取多边形的中心点

    package com.skjd.util; import java.util.ArrayList; import java.util.List; /** * 坐标以及电子围栏相关的工具类 * @au ...

  10. HttpSession与JSESSIONID的"盗用"

    https://blog.csdn.net/qq1437715969/article/details/75331652