|
@@ -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个点云的汇总点云,清零,然后再更新
|