Ver código fonte

解决分割方法特征提取内存泄露问题

zx 2 anos atrás
pai
commit
375b354cc2

+ 1 - 1
config/horizon_config.yaml

@@ -18,4 +18,4 @@ map_skip_frame: 2
 
 ivox_nearby_type: 26 #6  18 26
 max_ivox_node: 500
-ivox_node_solution: 0.5
+ivox_node_solution: 0.3

+ 2 - 2
lio/src/PoseEstimation.cpp

@@ -247,7 +247,7 @@ int main(int argc, char** argv)
   pMaper->SetCloudMappedCallback(CloudFullCallback);
   pMaper->SetLocalMapCloudCallback(CloudLocalCallback);
   pMaper->SetFinalCostCallback(FinalCostCallback);
-  pMaper->LoadMap(map_dir + "/feature.txt");
+  pMaper->LoadMap(map_dir + "/featurebbt.txt");
 
   double RPI = M_PI / 180.0;
   Eigen::Vector3d eulerAngle(0 * RPI, 0 * RPI, 5.0 * RPI);
@@ -295,7 +295,7 @@ int main(int argc, char** argv)
   // Specialisations mean no conversions take place for exact types
   // and conversions between scalar types are cheap.
   pangolin::Var<bool> lvx_checkbox("ui.lvx_Checkbox", false, true);
-  pangolin::Var<std::string> lvx_file("ui.lvx_file_String", "../map/gd.lvx");
+  pangolin::Var<std::string> lvx_file("ui.lvx_file_String", "../map/start1.lvx");
 
   pangolin::Var<bool> start_button("ui.start_Button", false, false);
   pangolin::Var<bool> stop_button("ui.stop_Button", false, false);

+ 12 - 12
lio/src/lio/Estimator.cpp

@@ -38,7 +38,7 @@ Estimator::Estimator(const float& filter_corner, const float& filter_surf,
   downSizeFilterSurf.setLeafSize(filter_surf, filter_surf, filter_surf);
   downSizeFilterNonFeature.setLeafSize(0.4, 0.4, 0.4);
 
-    local_map_.Init(ivox_nearby_type,max_ivox_node,resolution);
+    //local_map_.Init(ivox_nearby_type,max_ivox_node,resolution);
 }
 
 void Estimator::print()
@@ -182,7 +182,7 @@ void Estimator::processPointToLine(std::vector<ceres::CostFunction *>& edges,
 
     }
 
-    if(local_map_.CornerMapVox()->NumPoints()>20 )
+    /*if(local_map_.CornerMapVox()->NumPoints()>20 )
     {
         pcl::PointCloud<PointType> nearst;
         local_map_.CornerMapVox()->GetClosestPoint(_pointSel, nearst.points, 5, thres_dist);
@@ -267,7 +267,7 @@ void Estimator::processPointToLine(std::vector<ceres::CostFunction *>& edges,
                 vLineFeatures.back().ComputeError(m4d);
             }
         }
-    }
+    }*/
      
   }
 }
@@ -383,7 +383,7 @@ void Estimator::processPointToPlanVec(std::vector<ceres::CostFunction *>& edges,
     }
 
 
-    if(local_map_.surfMapVox()->NumPoints() > 20 )
+    /*if(local_map_.surfMapVox()->NumPoints() > 20 )
     {
         pcl::PointCloud<PointType> nearst;
         local_map_.surfMapVox()->GetClosestPoint(_pointSel, nearst.points, 5, thres_dist);
@@ -449,7 +449,7 @@ void Estimator::processPointToPlanVec(std::vector<ceres::CostFunction *>& edges,
                 vPlanFeatures.back().ComputeError(m4d);
             }
         }
-    }
+    }*/
 
   }
 
@@ -563,7 +563,7 @@ void Estimator::processNonFeatureICP(std::vector<ceres::CostFunction *>& edges,
 
     }
 
-    if (local_map_.NonfMapVox()->NumPoints() > 20)
+    /*if (local_map_.NonfMapVox()->NumPoints() > 20)
     {
       pcl::PointCloud<PointType> nearst;
       local_map_.NonfMapVox()->GetClosestPoint(_pointSel, nearst.points, 5, thres_dist);
@@ -619,7 +619,7 @@ void Estimator::processNonFeatureICP(std::vector<ceres::CostFunction *>& edges,
           vNonFeatures.back().ComputeError(m4d);
         }
       }
-    }
+    }*/
   }
 }
 
@@ -673,13 +673,13 @@ void Estimator::EstimateLidarPose(std::list<LidarFrame>& lidarFrameList,
   int laserCloudSurfFromMapNum = m_global_map.laserCloudSurfFromLocal->points.size();
 
 
-  local_map_.CornerMapVox()->GetPoints(local_corner_cloud_.points);
+  /*local_map_.CornerMapVox()->GetPoints(local_corner_cloud_.points);
   local_map_.surfMapVox()->GetPoints(local_surf_cloud_.points);
   local_map_.NonfMapVox()->GetPoints(local_nonf_cloud_.points);
 
 
   int laserCloudCornerFromLocalNum = local_corner_cloud_.points.size();
-  int laserCloudSurfFromLocalNum = local_surf_cloud_.points.size();
+  int laserCloudSurfFromLocalNum = local_surf_cloud_.points.size();*/
   int stack_count = 0;
 
   //遍历2帧历史数据,将角点,平面点,无特征点,提取出,下采样
@@ -720,8 +720,8 @@ void Estimator::EstimateLidarPose(std::list<LidarFrame>& lidarFrameList,
   }
   //地图有点,执行优化, 更新当前点及历史点的状态
 
-  if (((laserCloudCornerFromMapNum > 0 && laserCloudSurfFromMapNum > 100) ||
-       (laserCloudCornerFromLocalNum > 0 && laserCloudSurfFromLocalNum > 100)))
+  if (((laserCloudCornerFromMapNum > 0 && laserCloudSurfFromMapNum > 100)/* ||
+       (laserCloudCornerFromLocalNum > 0 && laserCloudSurfFromLocalNum > 100)*/))
   {
     Estimate(lidarFrameList, exTlb, gravity);
   }
@@ -1271,7 +1271,7 @@ void Estimator::MapIncrementLocal(const pcl::PointCloud<PointType>::Ptr& laserCl
   }
 
 
-  local_map_.MapIncrement(down_corner_transformed, down_surf_transformed, down_nonf_transformed, localMapID);
+  //local_map_.MapIncrement(down_corner_transformed, down_surf_transformed, down_nonf_transformed, localMapID);
 
 
     //本地地图50个点云的汇总点云,清零,然后再更新

+ 3 - 3
lio/src/lio/Estimator.h

@@ -329,11 +329,11 @@ public:
 
 	/** \brief store map points */
     Local_map m_global_map;
-    LocalMapIvox local_map_;
+    //LocalMapIvox local_map_;
 
-    pcl::PointCloud<PointType> local_corner_cloud_;
+    /*pcl::PointCloud<PointType> local_corner_cloud_;
     pcl::PointCloud<PointType> local_surf_cloud_;
-    pcl::PointCloud<PointType> local_nonf_cloud_;
+    pcl::PointCloud<PointType> local_nonf_cloud_;*/
     double final_cost_=0;
 
  private:

+ 2 - 3
lio/src/lio/mapper.cpp

@@ -551,7 +551,6 @@ void Mapper::process()
             },"Feature Extra"
     );
 
-
     RemoveLidarDistortion(cloudFull, delta_Rl, delta_tl);
 
     TimerRecord::Execute(
@@ -608,7 +607,7 @@ void Mapper::process()
       cloudMappedcallback_(laserCloudAfterEstimate, lidar_list->front().timeStamp);
     }
 
-    if (cloudLocalMappcallback_ != nullptr)
+    /*if (cloudLocalMappcallback_ != nullptr)
     {
 
       pcl::PointCloud<PointType> all;
@@ -618,7 +617,7 @@ void Mapper::process()
       all += estimator->local_nonf_cloud_;
 
       cloudLocalMappcallback_(all.makeShared(), lidar_list->front().timeStamp);
-    }
+    }*/
 
     if (final_cost_callback_ != nullptr)
     {

+ 2 - 0
lio/src/segment/LidarFeatureExtractor.cpp

@@ -1076,6 +1076,8 @@ void LidarFeatureExtractor::FeatureExtract_with_segment(pcl::PointCloud<PointTyp
             laserNonFeature->push_back(p);
     }
 
+    free(idtrans);
+    free(data);
 }