Commit a52b1340 authored by limingbo's avatar limingbo

init

parents
Pipeline #837 failed with stages
cmake_minimum_required(VERSION 2.8)
project(FeatrueExtract)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake)
find_package(PCL REQUIRED)
find_package(Boost REQUIRED COMPONENTS system filesystem regex program_options thread)
find_package(Glog REQUIRED)
find_package(GFlags REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARYIES})
include_directories(${CMAKE_CURRENT_SOURCE_DIR})
include_directories(${CMAKE_CURRENT_SOURCE_DIR}/libs)
add_subdirectory(apps)
add_subdirectory(libs)
add_subdirectory(proto)
find_package(PCL REQUIRED)
add_executable(pointCloudCompress compress.cpp)
target_include_directories(pointCloudCompress
PUBLIC
${PCL_INCLUDE_DIRS})
target_link_libraries(pointCloudCompress
${PCL_LIBRARIES}
${Boost_LIBRARIES}
${GLOG_LIBRARIES}
${GFLAGS_LIBRARIES}
dispatch
serialize)
add_executable(pointCloudExtract extract.cpp)
target_include_directories(pointCloudExtract
PUBLIC
${PCL_INCLUDE_DIRS})
target_link_libraries(pointCloudExtract
${PCL_LIBRARIES}
${Boost_LIBRARIES}
${GLOG_LIBRARIES}
${GFLAGS_LIBRARIES}
stream_info)
#include <iostream>
#include <gflags/gflags.h>
#include <glog/logging.h>
#include "dispatch/dispatch.h"
#include "serialize/blockserializer.h"
using namespace std;
DEFINE_string(pcd_dir, "", "pcd_dir");
void signaleHandle(const char* data, int size){
string str = data;
LOG(INFO) << "signaleHandle: " << str;
}
int main(int argc, char *argv[])
{
gflags::ParseCommandLineFlags(&argc, &argv, true);
google::InitGoogleLogging(argv[0]);
google::InstallFailureSignalHandler();
google::InstallFailureWriter(&signaleHandle);
FLAGS_log_dir = "/home/juefx/log";
FLAGS_alsologtostderr = true;
FLAGS_colorlogtostderr = true;
FLAGS_stderrthreshold = 0;
FLAGS_logbufsecs = 0;
Dispatch dispatch(FLAGS_pcd_dir);
dispatch.dispatch();
LOG(INFO) << "dispatch done";
boost::shared_ptr<GridManager> blockManager =
dispatch.getBlockManager();
BlockSerializer blockSerializer(blockManager);
blockSerializer.setOffset(dispatch.getOffset());
blockSerializer.configSerialization();
return 0;
}
#include <iostream>
#include <gflags/gflags.h>
#include <glog/logging.h>
#include "stream_info/streaminfo.h"
using namespace std;
DEFINE_string(stream_dir, "", "stream_dir");
void signaleHandle(const char* data, int size){
string str = data;
LOG(INFO) << "signaleHandle: " << str;
}
int main(int argc, char *argv[])
{
gflags::ParseCommandLineFlags(&argc, &argv, true);
google::InitGoogleLogging(argv[0]);
google::InstallFailureSignalHandler();
google::InstallFailureWriter(&signaleHandle);
FLAGS_log_dir = "/home/juefx/log";
FLAGS_alsologtostderr = true;
FLAGS_colorlogtostderr = true;
FLAGS_stderrthreshold = 0;
FLAGS_logbufsecs = 0;
StreamInfo streamInfo(FLAGS_stream_dir);
return 0;
}
# - Try to find GFLAGS
#
# The following variables are optionally searched for defaults
# GFLAGS_ROOT_DIR: Base directory where all GFLAGS components are found
#
# The following are set after configuration is done:
# GFLAGS_FOUND
# GFLAGS_INCLUDE_DIRS
# GFLAGS_LIBRARIES
# GFLAGS_LIBRARYRARY_DIRS
include(FindPackageHandleStandardArgs)
set(GFLAGS_ROOT_DIR "" CACHE PATH "Folder contains Gflags")
# We are testing only a couple of files in the include directories
if(WIN32)
find_path(GFLAGS_INCLUDE_DIR gflags/gflags.h
PATHS ${GFLAGS_ROOT_DIR}/src/windows)
else()
find_path(GFLAGS_INCLUDE_DIR gflags/gflags.h
PATHS ${GFLAGS_ROOT_DIR})
endif()
if(MSVC)
find_library(GFLAGS_LIBRARY_RELEASE
NAMES libgflags
PATHS ${GFLAGS_ROOT_DIR}
PATH_SUFFIXES Release)
find_library(GFLAGS_LIBRARY_DEBUG
NAMES libgflags-debug
PATHS ${GFLAGS_ROOT_DIR}
PATH_SUFFIXES Debug)
set(GFLAGS_LIBRARY optimized ${GFLAGS_LIBRARY_RELEASE} debug ${GFLAGS_LIBRARY_DEBUG})
else()
find_library(GFLAGS_LIBRARY gflags)
endif()
find_package_handle_standard_args(GFLAGS DEFAULT_MSG
GFLAGS_INCLUDE_DIR GFLAGS_LIBRARY)
if(GFLAGS_FOUND)
set(GFLAGS_INCLUDE_DIRS ${GFLAGS_INCLUDE_DIR})
set(GFLAGS_LIBRARIES ${GFLAGS_LIBRARY})
endif()
# Look for GeographicLib
#
# Set
# GeographicLib_FOUND = GEOGRAPHICLIB_FOUND = TRUE
# GeographicLib_INCLUDE_DIRS = /usr/local/include
# GeographicLib_LIBRARIES = /usr/local/lib/libGeographic.so
# GeographicLib_LIBRARY_DIRS = /usr/local/lib
find_library (GeographicLib_LIBRARIES Geographic
PATHS "${CMAKE_INSTALL_PREFIX}/../GeographicLib/lib")
if (GeographicLib_LIBRARIES)
get_filename_component (GeographicLib_LIBRARY_DIRS
"${GeographicLib_LIBRARIES}" PATH)
get_filename_component (_ROOT_DIR "${GeographicLib_LIBRARY_DIRS}" PATH)
set (GeographicLib_INCLUDE_DIRS "${_ROOT_DIR}/include")
set (GeographicLib_BINARY_DIRS "${_ROOT_DIR}/bin")
if (NOT EXISTS "${GeographicLib_INCLUDE_DIRS}/GeographicLib/Config.h")
# On Debian systems the library is in e.g.,
# /usr/lib/x86_64-linux-gnu/libGeographic.so
# so try stripping another element off _ROOT_DIR
get_filename_component (_ROOT_DIR "${_ROOT_DIR}" PATH)
set (GeographicLib_INCLUDE_DIRS "${_ROOT_DIR}/include")
set (GeographicLib_BINARY_DIRS "${_ROOT_DIR}/bin")
if (NOT EXISTS "${GeographicLib_INCLUDE_DIRS}/GeographicLib/Config.h")
unset (GeographicLib_INCLUDE_DIRS)
unset (GeographicLib_LIBRARIES)
unset (GeographicLib_LIBRARY_DIRS)
unset (GeographicLib_BINARY_DIRS)
endif ()
endif ()
unset (_ROOT_DIR)
endif ()
include (FindPackageHandleStandardArgs)
find_package_handle_standard_args (GeographicLib DEFAULT_MSG
GeographicLib_LIBRARY_DIRS GeographicLib_LIBRARIES
GeographicLib_INCLUDE_DIRS)
mark_as_advanced (GeographicLib_LIBRARY_DIRS GeographicLib_LIBRARIES
GeographicLib_INCLUDE_DIRS)
# - Try to find Glog
#
# The following variables are optionally searched for defaults
# GLOG_ROOT_DIR: Base directory where all GLOG components are found
#
# The following are set after configuration is done:
# GLOG_FOUND
# GLOG_INCLUDE_DIRS
# GLOG_LIBRARIES
# GLOG_LIBRARYRARY_DIRS
include(FindPackageHandleStandardArgs)
set(GLOG_ROOT_DIR "" CACHE PATH "Folder contains Google glog")
if(WIN32)
find_path(GLOG_INCLUDE_DIR glog/logging.h
PATHS ${GLOG_ROOT_DIR}/src/windows)
else()
find_path(GLOG_INCLUDE_DIR glog/logging.h
PATHS ${GLOG_ROOT_DIR})
endif()
if(MSVC)
find_library(GLOG_LIBRARY_RELEASE libglog_static
PATHS ${GLOG_ROOT_DIR}
PATH_SUFFIXES Release)
find_library(GLOG_LIBRARY_DEBUG libglog_static
PATHS ${GLOG_ROOT_DIR}
PATH_SUFFIXES Debug)
set(GLOG_LIBRARY optimized ${GLOG_LIBRARY_RELEASE} debug ${GLOG_LIBRARY_DEBUG})
else()
find_library(GLOG_LIBRARY glog
PATHS ${GLOG_ROOT_DIR}
PATH_SUFFIXES
lib
lib64)
endif()
find_package_handle_standard_args(GLOG DEFAULT_MSG
GLOG_INCLUDE_DIR GLOG_LIBRARY)
if(GLOG_FOUND)
set(GLOG_INCLUDE_DIRS ${GLOG_INCLUDE_DIR})
set(GLOG_LIBRARIES ${GLOG_LIBRARY})
endif()
add_subdirectory(utils)
add_subdirectory(grid)
add_subdirectory(dispatch)
add_subdirectory(serialize)
add_subdirectory(feature)
add_subdirectory(stream_info)
add_subdirectory(voxel)
add_library(dispatch
SHARED
dispatch.cpp)
target_link_libraries(dispatch
grid
utils)
#include "dispatch.h"
#include "grid/block.h"
using namespace boost::filesystem;
Dispatch::Dispatch(const string &path)
{
blockManager_.reset(new GridManager(BlockResolution, 1000));
loadPCD(path);
float minX = numeric_limits<float>::max();
float minY = numeric_limits<float>::max();
float minZ = numeric_limits<float>::max();
for(const auto &point : pointcloud_->points){
minX = minX < point.x ? minX : point.x;
minY = minY < point.y ? minY : point.y;
minZ = minZ < point.z ? minZ : point.z;
}
offset_ = {minX - 30, minY - 30, minZ};
for(auto &point : pointcloud_->points){
point.x -= offset_.x();
point.y -= offset_.y();
}
}
bool Dispatch::loadPCD(const string &path)
{
pointcloud_ = PointCloudExport::Ptr(new PointCloudExport);
if(exists(path)){
pcl::io::loadPCDFile(path, *pointcloud_);
return true;
}else{
return false;
}
}
boost::shared_ptr<GridManager> Dispatch::getBlockManager()
{
return blockManager_;
}
void Dispatch::dispatch()
{
if(!pointcloud_){
LOG(WARNING) << "NO pointcloud_ !";
return;
}
// boost::function<void(const PointExport &)> dispatchFunc
// = boost::bind(&Dispatch::dispatchPoint, this, _1);
// multiThreadProcess<PointExport>(pointcloud_, dispatchFunc);
for(const auto &point : pointcloud_->points){
dispatchPoint(point);
}
auto blockGrids = blockManager_->getGridMap();
vector<boost::shared_ptr<GridBase>> blockGridVec;
for(auto iter = blockGrids->begin(); iter != blockGrids->end(); iter++){
blockGridVec.push_back(iter->second);
}
boost::function<void(boost::shared_ptr<GridBase>)> configFunc
= boost::bind(&Dispatch::configBlockInfo, this, _1);
syncProcess<boost::shared_ptr<GridBase>>(blockGridVec, configFunc);
// for(auto iter = blockGrids->begin(); iter != blockGrids->end(); iter++){
// BlockGrid* block = reinterpret_cast<BlockGrid*>(iter->second.get());
// block->configInfo();
// }
// PointCloudExport::Ptr pointcloud;
// auto blockGrids = blockManager_->getGridMap();
// for(auto iter = blockGrids->begin(); iter != blockGrids->end(); iter++){
// BlockGrid* block = reinterpret_cast<BlockGrid*>(iter->second.get());
// LOG(INFO) << block->getIndex().transpose();
// auto gridGrids = block->getGridMap();
// for(auto it = gridGrids->begin(); it != gridGrids->end(); it++){
// Grid* grid = reinterpret_cast<Grid*>(it->second.get());
// PointCloudExport::Ptr pc = grid->getPointCloud();
// if(pc && pointcloud && pc->size() > pointcloud->size()){
// pointcloud = pc;
// }
// }
// }
// if(pointcloud){
// pcl::io::savePCDFileBinary("/home/juefx/1.pcd", *pointcloud);
// }
}
Vector3f Dispatch::getOffset()
{
return offset_;
}
void Dispatch::dispatchPoint(const PointExport &point)
{
Vector2i blockIndex = blockManager_->getGridIndexByPoint(point);
BlockGrid* block = reinterpret_cast<BlockGrid*>(
blockManager_->getGrid(blockIndex, blockType).get());
Vector2i gridIndex = block->getGridIndexByPoint(point);
Grid* grid = reinterpret_cast<Grid*>(block->getGrid(gridIndex).get());
grid->addPoint(point);
// Vector2f suppo = block->getCenter() + grid->getCenter();
// LOG(INFO) << "point: " << point.getArray3fMap().transpose()
// << " blockIndex: " << blockIndex.transpose()
// << " gridIndex: " << gridIndex.transpose()
// << " suppo: " << suppo.transpose();
// sleep(1);
}
void Dispatch::configBlockInfo(
boost::shared_ptr<GridBase> blockGrid){
BlockGrid* block = reinterpret_cast<BlockGrid*>(blockGrid.get());
block->configInfo();
}
#ifndef DISPATCH_H
#define DISPATCH_H
#include "utils/basic_types.h"
#include "utils/basic_functions.h"
#include <boost/filesystem.hpp>
#include <pcl/io/pcd_io.h>
#include "utils/pcl_point_type.h"
#include "grid/gridmanager.h"
class Dispatch
{
public:
Dispatch(const string &path);
bool loadPCD(const string &path);
boost::shared_ptr<GridManager> getBlockManager();
void dispatch();
Vector3f getOffset();
private:
void dispatchPoint(const PointExport &point);
void configBlockInfo(
boost::shared_ptr<GridBase> blockGrid);
private:
PointCloudExport::Ptr pointcloud_;
boost::shared_ptr<GridManager> blockManager_;
Vector3f offset_ = Vector3f::Zero();
};
#endif // DISPATCH_H
add_library(feature SHARED featureExtraction.cpp)
target_link_libraries(feature
)
#include <iostream>
#include <string>
#include <pcl/common/common_headers.h>
#include <pcl/io/pcd_io.h>
#include <pcl/console/parse.h>
#include <pcl/point_types.h>
#include <algorithm>
#include "featureExtraction.h"
using namespace std;
bool featureExtraction::initializeGridFeature(PointCloudExport::Ptr cloud) {
if (cloud == nullptr || cloud->points.size() == 0) {
cout << "cloud or ptr of cloud is empty" << endl;
return false;
}
int maxRangeRoad = 0;
int minRangeRoad = 0;
int maxRangeNonRoad = 0;
int minRangeNonRoad = 0;
int numOfIndexNonRoad = 0;
int numOfIndexRoad = 0;
int maxScore = -9999;
vec_labeledPoint.clear();
vec_unlabeledPoint.clear();
vec_labeledPointIndex.clear();
vec_unlabeledPointIndex.clear();
for (int i = 0; i < cloud->points.size(); i++) {
f_xyzil point;
point.x = cloud->points[i].x;
point.y = cloud->points[i].y;
point.z = cloud->points[i].z;
point.intensity = cloud->points[i].intensity;
point.label = cloud->points[i].label;
if (point.label < 20000.1 && point.label>19999.9) {
vec_labeledPoint.push_back(point);
}
else {
vec_unlabeledPoint.push_back(point);
}
}
setRangeAndIndex();
toVolumePixelAndSort();
return true;
}
void featureExtraction::getFeature(vector<gridFeature>& result) {
if (vec_labeledPoint.size() != 0) {
gridFeature labeled;
labeled.minz_devidedByResolution = minRangeRoad / resolutionRoad;
labeled.deltaz_devidedByResolution = numOfIndexRoad;
labeled.labeled = true;
int sum = 0;
for (int i = 0; i < vec_labeledPoint.size(); i++) {
sum += vec_labeledPoint[i].intensity;
}
labeled.intensity = round((float)sum / (float)vec_labeledPoint.size());
result.push_back(labeled);
}
getNonRoadFeature(result);
}
void featureExtraction::getNonRoadFeature(vector<gridFeature>& result) {
int n = vec_unlabeledPointIndex.size();
if (n == 0) {
return;
}
float sum = 0;
for (int i = 0; i < n; i++) {
sum += vec_unlabeledPointIndex[i];
}
int average = round((float)sum / (float)n);
int upperBound = average;
int lowerBound = average;
for (int i = average; i < numOfIndexNonRoad; i++) {
for (int j = average; j >= 0; j--) {
float score = 0;
for (int k = j; k <= i; k++) {
if (binarySearch(k)) {
score += scoreHitHit;
}
else {
score += scoreHitMiss;
}
}
for (int k = 0; k < n; k++) {
if (vec_unlabeledPointIndex[k] > i || vec_unlabeledPointIndex[k] < j) {
score += scoreMissHit;
}
}
if (score >= maxScore) {
maxScore = score;
upperBound = i;
lowerBound = j;
}
}
}
gridFeature unlabeled;
unlabeled.minz_devidedByResolution = minRangeNonRoad / resolutionNonRoad + lowerBound;
unlabeled.deltaz_devidedByResolution = upperBound - lowerBound + 1;
unlabeled.labeled = false;
sum = 0;
for (int i = 0; i < vec_unlabeledPoint.size(); i++) {
sum += vec_unlabeledPoint[i].intensity;
}
unlabeled.intensity = round((float)sum / (float)vec_unlabeledPoint.size());
result.push_back(unlabeled);
}
bool featureExtraction::binarySearch(int target) {
int left = 0; int right = vec_unlabeledPointIndex.size() - 1;
while (left <= right) {
int mid = (right + left) / 2;
if (vec_unlabeledPointIndex[mid] == target)
return true;
else if (vec_unlabeledPointIndex[mid] < target)
left = mid + 1;
else if (vec_unlabeledPointIndex[mid] > target)
right = mid - 1;
}
return false;
}
void featureExtraction::setRangeAndIndex() {
//Ѱұ߽
float f_max = -9999.9, f_min = 9999.9;
for (size_t i = 0; i <vec_labeledPoint.size(); i++) {
f_max = max(f_max, vec_labeledPoint[i].z);
f_min = min(f_min, vec_labeledPoint[i].z);
}
//趨߽
maxRangeRoad = ceil(f_max * 100.0 / (float)resolutionRoad) * resolutionRoad;
minRangeRoad = floor(f_min * 100.0 / (float)resolutionRoad) * resolutionRoad;
//趨index
numOfIndexRoad = (maxRangeRoad- minRangeRoad) / resolutionRoad;
f_max = -9999.9; f_min = 9999.9;
for (size_t i = 0; i < vec_unlabeledPoint.size(); i++) {
f_max = max(f_max, vec_unlabeledPoint[i].z);
f_min = min(f_min, vec_unlabeledPoint[i].z);
}
//趨߽
maxRangeNonRoad = ceil(f_max * 100.0 / (float)resolutionNonRoad) * resolutionNonRoad;
minRangeNonRoad = floor(f_min * 100.0 / (float)resolutionNonRoad) * resolutionNonRoad;
//趨index
numOfIndexNonRoad = (maxRangeNonRoad - minRangeNonRoad) / resolutionNonRoad;
}
void featureExtraction::toVolumePixelAndSort() {
int z=0;
for (size_t i = 0; i < vec_labeledPoint.size(); i++) {
z = floor((vec_labeledPoint[i].z * 100 - (float)minRangeRoad) / (float)resolutionRoad);
if (z == numOfIndexRoad) {
z--;
}
vec_labeledPointIndex.push_back(z);
}
sort(vec_labeledPointIndex.begin(), vec_labeledPointIndex.end());
vec_labeledPointIndex.erase(unique(vec_labeledPointIndex.begin(), vec_labeledPointIndex.end()), vec_labeledPointIndex.end());
for (size_t i = 0; i < vec_unlabeledPoint.size(); i++) {
z = floor((vec_unlabeledPoint[i].z * 100 - (float)minRangeNonRoad) / (float)resolutionNonRoad);
if (z == numOfIndexNonRoad) {
z--;
}
vec_unlabeledPointIndex.push_back(z);
}
sort(vec_unlabeledPointIndex.begin(), vec_unlabeledPointIndex.end());
vec_unlabeledPointIndex.erase(unique(vec_unlabeledPointIndex.begin(), vec_unlabeledPointIndex.end()), vec_unlabeledPointIndex.end());
}
#pragma once
#include <iostream>
#include <string>
#include <pcl/common/common_headers.h>
#include <pcl/io/pcd_io.h>
#include <pcl/console/parse.h>
#include <pcl/point_types.h>
#include "utils/pcl_point_type.h"
#include <algorithm>
#include <vector>
using namespace std;
struct gridFeature {
int minz_devidedByResolution = 0;
int deltaz_devidedByResolution = 0;
int intensity = 0;
bool labeled = false;
};
struct f_xyzil {
float x = 0;
float y = 0;
float z = 0;
float intensity = 0;
float label = 0;
};
class featureExtraction {
public:
featureExtraction(int resolutionRoad=3,int resolutionNonRoad=3) {
setResolution(resolutionRoad, resolutionNonRoad);
};
~featureExtraction() {};
bool initializeGridFeature(PointCloudExport::Ptr);
void setResolution(int resolutionRoad , int resolutionNonRoad ) {
this->resolutionRoad = resolutionRoad;
this->resolutionNonRoad = resolutionNonRoad;
};
void getFeature(vector<gridFeature>&);
private:
void setRangeAndIndex();
void toVolumePixelAndSort();
void getNonRoadFeature(vector<gridFeature>&);
bool binarySearch(int);
int maxRangeRoad = 0;
int minRangeRoad = 0;
int maxRangeNonRoad = 0;
int minRangeNonRoad = 0;
int resolutionRoad;
int resolutionNonRoad;
int numOfIndexNonRoad = 0;
int numOfIndexRoad = 0;
float scoreHitMiss = -0.1;
float scoreHitHit = 1;
float scoreMissHit = -0.1;
int maxScore = -9999;
vector<f_xyzil> vec_labeledPoint;
vector<f_xyzil> vec_unlabeledPoint;
vector<int> vec_labeledPointIndex;
vector<int> vec_unlabeledPointIndex;
};
add_library(grid
SHARED
gridbase.cpp
block.cpp
grid.cpp
gridmanager.cpp)
target_link_libraries(grid
feature)
#include "block.h"
BlockGrid::BlockGrid(const Vector2i &index, float resolution)
:GridBase(index, resolution),
GridManager(GridResolution24cm, resolution)
{
setOrigin(GridBase::origin_);
}
void BlockGrid::configInfo()
{
// blockInfo_.set_local_offset_x(GridBase::center_.x());
// blockInfo_.set_local_offset_y(GridBase::center_.y());
auto gridGrids = getGridMap();
auto iter = gridGrids->begin();
distribution_.gridDistributions.resize(pow(BlockResolution / GridManager::resolution_, 2));
for( ; iter != gridGrids->end(); iter++){
Grid* grid = reinterpret_cast<Grid*>(iter->second.get());
grid->configInfo();
if(grid->getHasGround()){
hasGround_ = true;
break;
}
GridDistribution_ distributions = grid->getGridDistribution();
uint32_t grid_id = iter->first;
distribution_.gridDistributions.at(grid_id) = distributions;
}
if(hasGround_){
GridManager::setResolution(GridResolution6cm);
PointCloudExport::Ptr pointcloud = getBlockPointcloud();
reDispatch(pointcloud);
auto gridGrids = getGridMap();
auto iter = gridGrids->begin();
distribution_.gridDistributions.clear();
distribution_.gridDistributions.resize(pow(BlockResolution / GridManager::resolution_, 2));
for( ; iter != gridGrids->end(); iter++){
Grid* grid = reinterpret_cast<Grid*>(iter->second.get());
grid->configInfo();
GridDistribution_ distributions = grid->getGridDistribution();
uint32_t grid_id = iter->first;
distribution_.gridDistributions.at(grid_id) = distributions;
}
}
}
BlockInfo BlockGrid::getBlockInfo()
{
return blockInfo_;
}
BlockDistribution_ BlockGrid::getDistributions()
{
return distribution_;
}
PointCloudExport::Ptr BlockGrid::getBlockPointcloud()
{
PointCloudExport::Ptr pointcloud;
pointcloud.reset(new PointCloudExport);
auto gridGrids = getGridMap();
auto iter = gridGrids->begin();
for( ; iter != gridGrids->end(); iter++){
Grid* grid = reinterpret_cast<Grid*>(iter->second.get());
*pointcloud += *grid->getPointCloud();
}
return pointcloud;
}
void BlockGrid::reDispatch(PointCloudExport::Ptr pointcloud)
{
grids_.reset(new map<uint32_t, boost::shared_ptr<GridBase>>);
for(auto point :pointcloud->points){
Vector2i gridIndex = getGridIndexByPoint(point);
Grid* grid = reinterpret_cast<Grid*>(getGrid(gridIndex).get());
grid->addPoint(point);;
}
}
#ifndef BLOCK_H
#define BLOCK_H
#include "gridbase.h"
#include "grid.h"
#include "gridmanager.h"
#include "proto_pb/block/block_info.pb.h"
class BlockGrid : public GridBase, public GridManager
{
public:
BlockGrid(const Vector2i &index, float resolution);
void configInfo();
BlockInfo getBlockInfo();
BlockDistribution_ getDistributions();
private:
PointCloudExport::Ptr getBlockPointcloud();
void reDispatch(PointCloudExport::Ptr pointcloud);
private:
BlockInfo blockInfo_;
BlockDistribution_ distribution_;
bool hasGround_ = false;
};//end of class
#endif // BLOCK_H
#include<iostream>
#include <pcl/common/common_headers.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <vector>
#include <math.h>
#include <string>
using namespace std;
struct extrac{
int minz_devidedBy3 = 0; //最低高度/3cm
int deltaz_devidedBy3 = 0; //高度差/3cm
int intensity = 0; //平均密度
bool labeled = false; //是否被label为地面
};
//读取PointExport类型点云,并转换为PointXYZI类型点云,当labeled为true时表示对标记为地面的点云操作
bool exportToXYZILabeled(const pcl::PointCloud<pcl::PointExport>::Ptr cloudMixed,pcl::PointCloud<pcl::PointXYZI>::Ptr cloud, bool labeled)
{
if(cloudMixed==nullptr||cloudMixed->points.size()==0||cloud==nullptr){
return false;
}
cloud->height=1;
cloud->is_dense =false;
for(size_t i=0;i<cloudMixed->points.size();i++){
if((cloudMixed->points[i].label>19999.99&&cloudMixed->points[i].label<20000.01&&labeled==true)||
((cloudMixed->points[i].label<19999.99||cloudMixed->points[i].label>20000.01)&&labeled==false)){
cloud->width+=1;
cloud->points.resize(cloud->width);
int j=cloud->width-1;
cloud->points[j].x=cloudMixed->points[i].x;
cloud->points[j].y=cloudMixed->points[i].y;
cloud->points[j].z=cloudMixed->points[i].z;
cloud->points[j].intensity=cloudMixed->points[i].intensity;
//cout<<setw(16)<<cloud->points[j].x<<setw(16)<<cloud->points[j].y<<setw(16)<<cloud->points[j].z<<setw(16)<<cloud->points[j].intensity<<endl;
}
}
if(cloud->points.size()==0){
return false;
}
//cout<<endl;
return true;
}
//读取按label分完类的点云,并返回点云的最低高度,高度差和反射率,当labeled为true时表示对标记为地面的点云操作
extrac extract(pcl::PointCloud<pcl::PointXYZI>::Ptr cloud,bool labeled)
{
extrac ret;
int n=cloud->points.size();
if(n==0){
return {0,0,0};
}
float maxz=-99999.0,minz=99999.0,sum=0;
for(int i=0;i<n;i++)
{
sum+=cloud->points[i].intensity;
maxz=max(cloud->points[i].z,maxz);
minz=min(cloud->points[i].z,minz);
}
//cout<<setw(16)<<maxz<<setw(16)<<minz<<endl;
ret.intensity=round(sum/(float)n);
//以下已转换为厘米 label的地面高度最小值取四舍五入,高度差取小,unlabel部分高度最小值取小,高度差取大
if(labeled){
ret.minz_devidedBy3=round(minz*100.0/3.0);
ret.deltaz_devidedBy3=floor((maxz-minz)*100.0/3.0);
if(ret.deltaz_devidedBy3==0){
ret.deltaz_devidedBy3=1;
}
ret.labeled=true;
}else{
ret.minz_devidedBy3=floor(minz*100.0/3.0)-1;
ret.deltaz_devidedBy3=ceil((maxz-minz)*100.0/3.0);
ret.labeled=false;
}
return ret;
}
//此为函数的入口,输入为PointExport点云指针,输出为extrac结构体类型的vector,结构体前两项为最低高度和高度差,单位为(3厘米);第三项为反射率,为整数;第四项为bool型,true代表该分部被地面label
vector<extrac> extractFromBlock (pcl::PointCloud<pcl::PointExport>::Ptr cloudMixed){
vector<extrac> ret;
if(!cloudMixed||cloudMixed->points.size()==0){
return ret;
}
pcl::PointCloud<pcl::PointXYZI>::Ptr cloudLabeled(new pcl::PointCloud<pcl::PointXYZI>);
pcl::PointCloud<pcl::PointXYZI>::Ptr cloudUnlabeled(new pcl::PointCloud<pcl::PointXYZI>);
if(exportToXYZILabeled(cloudMixed,cloudLabeled,true)){
ret.push_back(extract(cloudLabeled,true));
}
if(exportToXYZILabeled(cloudMixed,cloudUnlabeled,false)){
ret.push_back(extract(cloudUnlabeled,false));
};
return ret;
}
#include "grid.h"
#include "extractFunction.h"
#include "feature/featureExtraction.h"
Grid::Grid(const Vector2i &index, float resolution)
:GridBase(index, resolution)
{
pointcloud_.reset(new PointCloudExport);
}
void Grid::addPoint(const PointExport &point)
{
// boost::unique_lock<boost::shared_mutex> lock(insertMtx_);
pointcloud_->push_back(point);
}
PointCloudExport::Ptr Grid::getPointCloud()
{
return pointcloud_;
}
void Grid::configInfo()
{
// float zMax = numeric_limits<float>::lowest();
// float zMin = numeric_limits<float>::max();
// for(const auto &point : pointcloud_->points){
// zMax = zMax > point.z ? zMax : point.z;
// zMin = zMin < point.z ? zMin : point.z;
// }
// OneDistribution_ oneDistribution;
// oneDistribution.floor = floor(zMin / ZResolution);
// oneDistribution.z_delta_leval = (zMax - zMin) / ZResolution;
// gridDtribution_.oneDistributions.push_back(oneDistribution);
// vector<extrac> ret = extractFromBlock(pointcloud_);
// for(const extrac& distribution : ret){
// OneDistribution_ oneDistribution;
// oneDistribution.floor = distribution.minz_devidedBy3;
// oneDistribution.z_delta_level = distribution.deltaz_devidedBy3;
// oneDistribution.intensity = distribution.intensity / 8;
// gridDtribution_.oneDistributions.push_back(oneDistribution);
// }
vector<gridFeature> result;
//构建特征提取类
featureExtraction fe;
//使用点云初始化
fe.initializeGridFeature(pointcloud_);
//获取结果
fe.getFeature(result);
for(const gridFeature& distribution : result){
OneDistribution_ oneDistribution;
oneDistribution.floor = distribution.minz_devidedByResolution;
oneDistribution.z_delta_level = distribution.deltaz_devidedByResolution;
oneDistribution.intensity = distribution.intensity / 8;
gridDtribution_.oneDistributions.push_back(oneDistribution);
hasGround_ = hasGround_ || distribution.labeled;
}
}
GridDistribution_ Grid::getGridDistribution()
{
return gridDtribution_;
}
bool Grid::getHasGround()
{
return hasGround_;
}
#ifndef GRID_H
#define GRID_H
#include "gridbase.h"
#include "utils/pcl_point_type.h"
#include "proto_pb/distribution/distribution.pb.h"
class Grid : public GridBase
{
public:
Grid(const Vector2i &index, float resolution);
void addPoint(const PointExport &point);
PointCloudExport::Ptr getPointCloud();
void configInfo();
GridDistribution_ getGridDistribution();
bool getHasGround();
private:
PointCloudExport::Ptr pointcloud_;
boost::shared_mutex insertMtx_;
GridDistribution_ gridDtribution_;
bool hasGround_ = false;
};
#endif // GRID_H
#include "gridbase.h"
GridBase::GridBase(
Vector2i index,
float resolution)
:index_(index),
resolution_(resolution)
{
origin_ = Vector2f((float)index_.x(), (float)index_.y()) * resolution_;
}
Vector2i GridBase::getIndex()
{
return index_;
}
float GridBase::getResolution()
{
return resolution_;
}
Vector2f GridBase::getOrigin()
{
return origin_;
}
#ifndef GRIDBASE_H
#define GRIDBASE_H
#include "utils/basic_types.h"
class GridBase
{
public:
GridBase(Vector2i index, float resolution);
Vector2i getIndex();
float getResolution();
Vector2f getOrigin();
virtual void configInfo() = 0;
protected:
Vector2f origin_ = Vector2f::Zero();
private:
Vector2i index_;
float resolution_;
};
#endif // GRIDBASE_H
#include "gridmanager.h"
#include "block.h"
GridManager::GridManager(
const float resolution,
const float sideLength)
:resolution_(resolution),
sideLength_(sideLength)
{
grids_.reset(new map<uint32_t, boost::shared_ptr<GridBase>>);
}
bool GridManager::getGrid(
const Vector2i &index,
boost::shared_ptr<GridBase> &grid)
{
uint32_t encodedIndex = encodeIndex(index);
auto iter = grids_->find(encodedIndex);
if(iter != grids_->end()){
grid = iter->second;
return true;
}else{
return false;
}
}
boost::shared_ptr<GridBase> GridManager::getGrid(
const Vector2i &index, const GridType type)
{
boost::shared_ptr<GridBase> grid;
uint32_t encodedIndex = encodeIndex(index);
auto iter = grids_->find(encodedIndex);
if(iter != grids_->end()){
grid = iter->second;
}else{
if(type == gridType){
grid = boost::shared_ptr<GridBase>(new Grid(index, resolution_));
}else if(type == blockType){
grid = boost::shared_ptr<GridBase>(new BlockGrid(index, resolution_));
}
grids_->insert(make_pair(encodedIndex, grid));
}
return grid;
}
void GridManager::addGridByIndex(
const Vector2i &index, const GridType type)
{
uint32_t encodedIndex = encodeIndex(index);
boost::shared_ptr<GridBase> grid;
if(type == gridType){
grid = boost::shared_ptr<GridBase>(new Grid(index, resolution_));
}else if(type == blockType){
grid = boost::shared_ptr<GridBase>(new BlockGrid(index, resolution_));
}
boost::unique_lock<boost::shared_mutex> lock(insertMtx_);
grids_->insert(make_pair(encodedIndex, grid));
}
Vector2i GridManager::getGridIndexByPoint(const PointExport &point)
{
Vector2i index;
index.x() = floor((point.x - origin_.x()) / resolution_);
index.y() = floor((point.y - origin_.y()) / resolution_);
return index;
}
void GridManager::setOrigin(const Vector2f &origin)
{
origin_ = origin;
}
const boost::shared_ptr<map<uint32_t, boost::shared_ptr<GridBase> > >
GridManager::getGridMap()
{
return grids_;
}
float GridManager::getResolution()
{
return resolution_;
}
void GridManager::setResolution(float resolution)
{
resolution_ = resolution;
}
void GridManager::setSideLength(float sideLength)
{
sideLength_ = sideLength;
}
uint32_t GridManager::encodeIndex(const Vector2i &index)
{
return index.x() * (uint32_t)(sideLength_ / resolution_) + index.y();
}
#ifndef GRIDMANAGER_H
#define GRIDMANAGER_H
#include "grid.h"
#include "utils/pcl_point_type.h"
class BlockGrid;
class GridManager
{
public:
GridManager(const float resolution,
const float sideLength);
bool getGrid(const Vector2i &index,
boost::shared_ptr<GridBase> &grid);
boost::shared_ptr<GridBase> getGrid(
const Vector2i &index, const GridType type = gridType);
void addGridByIndex(
const Vector2i &index, const GridType type = gridType);
Vector2i getGridIndexByPoint(const PointExport &point);
void setOrigin(const Vector2f &origin);
const boost::shared_ptr<map<uint32_t, boost::shared_ptr<GridBase>>>
getGridMap();
void setResolution(float resolution);
void setSideLength(float sideLength);
float getResolution();
protected:
uint32_t encodeIndex(const Vector2i &index);
protected:
Vector2f origin_ = Vector2f::Zero();
boost::shared_ptr<map<uint32_t, boost::shared_ptr<GridBase>>> grids_;
float resolution_;
float sideLength_;
private:
boost::shared_mutex insertMtx_;
};
#endif // GRIDMANAGER_H
add_library(serialize STATIC blockserializer.cpp)
target_link_libraries(serialize
proto_pb
${Boost_LIBRARIES})
#include "blockserializer.h"
#include "proto_pb/common/header.pb.h"
#include "proto_pb/block/block_index.pb.h"
#include "proto_pb/block/block_info.pb.h"
#include "utils/basic_functions.h"
BlockSerializer::BlockSerializer(
boost::shared_ptr<GridManager> blockManager)
:blockManager_(blockManager)
{
}
bool checkOneDistribution_(
const OneDistribution_ &source,
const OneDistribution_ &target){
if(source.floor == target.floor
&& source.z_delta_level == target.z_delta_level
&& source.intensity == target.intensity){
return true;
}else{
return false;
}
}
bool checkGridDistribution_(
const GridDistribution_ &source,
const GridDistribution_ &target){
if(source.oneDistributions.size()
!= target.oneDistributions.size()){
return false;
}
for(size_t i = 0; i < source.oneDistributions.size(); i++){
if(!checkOneDistribution_(
source.oneDistributions[i],
target.oneDistributions[i])){
return false;
}
}
return true;
}
struct DistributionInfo{
GridDistribution_ gridDistribution;
uint32_t cnt = 0;
uint32_t id = 0;
};
void BlockSerializer::configSerialization()
{
string serializedStream;
auto blockGrids = blockManager_->getGridMap();
// auto it = blockGrids->begin();
// for(int temp = 0; temp < 50; temp++){
// it++;
// }
// auto block = *it;
// blockGrids->clear();
// blockGrids->insert(make_pair(block.first, block.second));
vector<BlockInfo_> blockInfoVec;
vector<DistributionInfo> distributionInfoVec;
LOG(INFO) << "blockGrids->size(): " << blockGrids->size();
map<int64_t, DistributionInfo> distributionMap;
for(auto iter = blockGrids->begin(); iter != blockGrids->end(); iter++){
BlockGrid* block = reinterpret_cast<BlockGrid*>(iter->second.get());
int32_t blockId = iter->first;
BlockDistribution_ blockDistribution =
block->getDistributions();
for(size_t grid_id = 0; grid_id < blockDistribution.gridDistributions.size(); grid_id++){
GridDistribution_ gridDistribution = blockDistribution.gridDistributions[grid_id];
int64_t key = gridDistribution.getScore();
if(key == 0){
continue;
}
auto iter = distributionMap.find(key);
if(iter == distributionMap.end()){
DistributionInfo distributionInfo;
distributionInfo.gridDistribution = gridDistribution;
// distributionInfo.id = distributionInfoVec.size();
// distributionInfoVec.push_back(distributionInfo);
distributionMap.insert(make_pair(key, distributionInfo));
}else{
iter->second.cnt++;
}
}
BlockInfo_ blockInfo_;
blockInfo_.block_id = blockId;
blockInfo_.grid_resolution = block->GridManager::getResolution();
blockInfo_.bit_map.resize(pow(BlockResolution / block->GridManager::getResolution(), 2) / 8);
// blockInfo_.grid_feature_index.resize(90000, 0);
blockInfoVec.push_back(blockInfo_);
}
//// vector<DistributionInfo> distributionInfoVec;
///
for(auto iter = distributionMap.begin(); iter != distributionMap.end(); iter++){
distributionInfoVec.push_back(iter->second);
}
sort(distributionInfoVec.begin(),
distributionInfoVec.end(),
[](const DistributionInfo& query, const DistributionInfo& target) {
return query.cnt > target.cnt;
});
map<int64_t, DistributionInfo>().swap(distributionMap);
for(size_t i = 0; i < distributionInfoVec.size(); i++){
auto distributionInfo = distributionInfoVec[i];
distributionInfo.id = i;
distributionMap.insert(make_pair(distributionInfo.gridDistribution.getScore(), distributionInfo));
}
LOG(INFO) << "distributionInfoVec.size(): " << distributionInfoVec.size();
size_t index = 0;
for(auto iter = blockGrids->begin(); iter != blockGrids->end(); iter++){
BlockGrid* block = reinterpret_cast<BlockGrid*>(iter->second.get());
BlockDistribution_ blockDistribution =
block->getDistributions();
uint8_t byte = 0;
for(size_t grid_id = 0; grid_id < blockDistribution.gridDistributions.size(); grid_id++){
GridDistribution_ gridDistribution = blockDistribution.gridDistributions[grid_id];
uint32_t byteIndex = grid_id / 8;
uint8_t bitIndex = grid_id % 8;
int64_t key = gridDistribution.getScore();
auto iter = distributionMap.find(key);
if(iter != distributionMap.end()){
size_t distributionId = iter->second.id;
byte |= 1 << bitIndex;
blockInfoVec[index].active_grid_feature_index.push_back(distributionId);
blockInfoVec[index].whole_grid_feature_index.push_back(distributionId + 1);
}else{
blockInfoVec[index].whole_grid_feature_index.push_back(0);
}
if(bitIndex == 7){
blockInfoVec[index].bit_map[byteIndex] = byte;
byte = 0;
}
}
blockInfoVec[index].bit_map.back() = byte;
index++;
}
/////////// BlockIndex /////////////
/// \brief blockIndex
///
BlockIndex blockIndex;
/////////// BlockInfo /////////////
/// \brief blockInfo
///
string blockInfoBitmapStream, blockInfoIndexStream;
uint32_t block_offset = 0;
LOG(INFO) << "blockInfoVec.size(): " << blockInfoVec.size();
int cnt = 0;
for(auto &blockInfo_ : blockInfoVec){
BlockInfo blockInfoBitmap;
for(auto byte : blockInfo_.bit_map){
blockInfoBitmap.add_bit_map(byte);
}
for(auto gridIndex : blockInfo_.active_grid_feature_index){
blockInfoBitmap.add_grid_feature_index(gridIndex);
}
cnt++;
blockInfoBitmap.set_grid_resolution(blockInfo_.grid_resolution);
blockInfoBitmapStream += blockInfoBitmap.SerializeAsString();
BlockDescribe* blockDescribe = blockIndex.add_block_describe();
blockDescribe->set_block_id(blockInfo_.block_id);
blockDescribe->set_block_info_offset(block_offset);
block_offset = blockInfoBitmapStream.size();
BlockInfo blockInfoIndex;
for(auto gridIndex : blockInfo_.whole_grid_feature_index){
blockInfoIndex.add_grid_feature_index(gridIndex);
}
blockInfoIndexStream += blockInfoIndex.SerializeAsString();
}
LOG(INFO) << "cnt: " << cnt;
Distributions distributions;
for(auto &distributionInfo : distributionInfoVec){
GridDistribution* gridDistribution = distributions.add_grid_distribution();
for(auto &oneDistribution : distributionInfo.gridDistribution.oneDistributions){
OneDistribution* protoOneDistribution = gridDistribution->add_one_distribution();
protoOneDistribution->set_floor(oneDistribution.floor);
protoOneDistribution->set_z_delta_leval(oneDistribution.z_delta_level);
protoOneDistribution->set_intensity(oneDistribution.intensity);
}
}
/////////// Header /////////////
/// \brief header
///
Header header;
header.set_save_type(Header_SaveType_DIRECT);
header.set_mesh_level(15);
header.set_block_relolution(BlockResolution);
header.set_grid_relolution(GridResolution6cm);
header.set_offset_x(offset_.x());
header.set_offset_y(offset_.y());
header.set_longtitude(121.131722586496);
header.set_latitude(31.1529105050223);
header.set_height(0);
LOG(INFO) << "blockInfoBitmapStream.size(): " << blockInfoBitmapStream.size();
LOG(INFO) << "blockInfoIndexStream.size(): " << blockInfoIndexStream.size();
string blockInfoStream;
if(blockInfoBitmapStream.size() < blockInfoIndexStream.size()){
blockInfoStream = blockInfoBitmapStream;
header.set_save_type(Header_SaveType_BIT);
LOG(INFO) << "Header_SaveType_BIT";
}else{
blockInfoStream = blockInfoIndexStream;
header.set_save_type(Header_SaveType_DIRECT);
LOG(INFO) << "Header_SaveType_DIRECT";
}
header.set_active_block_count(blockGrids->size());
LOG(INFO) << "blockIndex.block_describe_size(): " << blockIndex.block_describe_size();
string blockIndexStream = blockIndex.SerializeAsString();
string distributionsStream = distributions.SerializeAsString();
header.set_block_index_length(blockIndexStream.size());
header.set_block_info_length(blockInfoBitmapStream.size());
string headerStream = header.SerializeAsString();
serializedStream += headerStream;
LOG(INFO) << "headerStream.size(): " << headerStream.size();
serializedStream += blockIndexStream;
LOG(INFO) << "blockIndexStream.size(): " << blockIndexStream.size();
serializedStream += blockInfoStream;
LOG(INFO) << "blockInfoStream.size(): " << blockInfoStream.size();
serializedStream += distributionsStream;
LOG(INFO) << "distributionsStream.size(): " << distributionsStream.size();
uint16_t headerSize = headerStream.size();
string path = "/home/juefx/temp.stream";
std::ofstream ofs(path, ios::binary);
if(!ofs){
LOG(WARNING) << path << " load fail!";
return;
}
ofs << (char)headerSize << (char)(headerSize >> 8);
ofs << serializedStream;
\
ofs.close();
}
void BlockSerializer::setOffset(const Vector3f &offset)
{
offset_ = offset;
}
#ifndef BLOCKSERIALIZER_H
#define BLOCKSERIALIZER_H
#include "grid/gridmanager.h"
#include "grid/block.h"
class BlockSerializer
{
public:
BlockSerializer(boost::shared_ptr<GridManager> blockManager);
void configSerialization();
void setOffset(const Vector3f &offset);
private:
private:
boost::shared_ptr<GridManager> blockManager_;
vector<IndexDistribution> indexDistributionVec_;
boost::shared_mutex mtx_;
Vector3f offset_ = Vector3f::Zero();
};
#endif // BLOCKSERIALIZER_H
find_package(GeographicLib REQUIRED)
add_library(stream_info
STATIC
streaminfo.cpp)
target_include_directories(stream_info
PUBLIC
${GeographicLib_INCLUDE_DIRS})
target_link_libraries(stream_info
utils
proto_pb
voxel
${GeographicLib_LIBRARIES})
#include "streaminfo.h"
StreamInfo::StreamInfo(const string &streamPath)
:streamPath_(streamPath)
{
extractedPointcloud_.reset(new PointCloudXYZI);
load();
}
void StreamInfo::load()
{
ifstream infile(streamPath_, ios::binary);
if(!infile)
{
LOG(WARNING) << streamPath_ << " open error!";
return ;
}
char buf[2];
infile.read(buf, 2);
headerLength_ = ((uint16_t)buf[1] << 8) + (uint16_t)buf[0];
LOG(INFO) << "headerLength: " << headerLength_;
char* headerData = (char*)malloc(headerLength_);
infile.read(headerData, headerLength_);
header_.ParseFromArray(headerData, headerLength_);
free(headerData);
float grid_relolution = header_.grid_relolution();
float block_relolution = header_.block_relolution();
offset_.x() = header_.offset_x();
offset_.y() = header_.offset_y();
LOG(INFO) << "grid_relolution: " << grid_relolution;
LOG(INFO) << "block_relolution: " << block_relolution;
proj_.reset(new LocalCartesian(header_.latitude(),
header_.longtitude(),
header_.height()));
uint16_t blockIndexLength = header_.block_index_length();
LOG(INFO) << "blockIndexLength: " << blockIndexLength;
char* blockIndexData = (char*)malloc(blockIndexLength);
infile.read(blockIndexData, blockIndexLength);
blockIndex_.ParseFromArray(blockIndexData, blockIndexLength);
free(blockIndexData);
size_t block_describe_size = blockIndex_.block_describe_size();
for(size_t i = 0; i < block_describe_size; i++){
BlockDescribe blockDescribe = blockIndex_.block_describe(i);
Internal::BlockDescribe internalBlockDescribe;
internalBlockDescribe.blockId = blockDescribe.block_id();
internalBlockDescribe.blockOffset = blockDescribe.block_info_offset();
if(i != 0){
blockDescribeVec_.back().blockSize =
internalBlockDescribe.blockOffset - blockDescribeVec_.back().blockOffset;
}
blockDescribeVec_.push_back(internalBlockDescribe);
}
blockDescribeVec_.back().blockSize =
header_.block_info_length() - blockDescribeVec_.back().blockOffset;
LOG(INFO) << "block_describe_size: " << block_describe_size;
infile.clear();
infile.seekg(0, infile.end);
uint32_t totalSize = infile.tellg();
LOG(INFO) << "infile.tellg(): " << infile.tellg();
infile.clear();
infile.seekg(2 + headerLength_ +
header_.block_index_length() + header_.block_info_length());
uint32_t distributionSize = totalSize - 2 - headerLength_ -
header_.block_index_length() - header_.block_info_length();
char* distributionBuf = (char*)malloc(distributionSize);
LOG(INFO) << "distributionSize: " << distributionSize;
infile.read(distributionBuf, distributionSize);
infile.close();
Distributions_.ParseFromArray(distributionBuf, distributionSize);
free(distributionBuf);
LOG(INFO) << "Distributions_.grid_distribution_size(): " << Distributions_.grid_distribution_size();
for(size_t i = 0; i < blockDescribeVec_.size(); i++){
auto blockDescribe = blockDescribeVec_[i];
parseOneBlock(blockDescribe);
// if(extractedPointcloud_->size()){
// pcl::io::savePCDFileBinary(
// "/home/juefx/temp/" + to_string(i) + "_block.pcd", *extractedPointcloud_);
// }
// extractedPointcloud_->clear();
}
LOG(INFO) << "extractedPointcloud_.size(): " << extractedPointcloud_->size();
if(extractedPointcloud_->size()){
pcl::io::savePCDFileBinary("/home/juefx/extracted.pcd", *extractedPointcloud_);
}
// voxel_.calculateHits(extractedPointcloud_);
}
void StreamInfo::parseOneBlock(
const Internal::BlockDescribe &internalBlockDescribe)
{
ifstream infile(streamPath_, ios::binary);
if(!infile)
{
LOG(WARNING) << streamPath_ << " open error!";
return ;
}
char* blockInfoData = (char*)malloc(internalBlockDescribe.blockSize);
uint32_t infoOffset = 2 + headerLength_ + header_.block_index_length() + internalBlockDescribe.blockOffset;
infile.clear();
infile.seekg(infoOffset);
infile.read(blockInfoData, internalBlockDescribe.blockSize);
BlockInfo blockInfo;
blockInfo.ParseFromArray(blockInfoData, internalBlockDescribe.blockSize);
free(blockInfoData);
infile.close();
// LOG(INFO) << "blockIndexX: " << blockIndexX;
// LOG(INFO) << "blockIndexY: " << blockIndexY;
// LOG(INFO) << "blockCenterX: " << blockCenterX;
// LOG(INFO) << "blockCenterY: " << blockCenterY;
if(blockInfo.bit_map_size()){
parseBitmapBlock(blockInfo, internalBlockDescribe);
}else{
parseIndexBlock(blockInfo, internalBlockDescribe);
}
}
vector<uint32_t> StreamInfo::parseBitMap(
const ProtoRepeatedUint32 &bitmap,
const uint32_t size)
{
vector<uint32_t> activeGridIndexes;
uint32_t activeGridIndex = 0;
for(size_t i = 0; i < size; i++){
uint8_t byte = bitmap.Get(i);
for(size_t byteCnt = 0; byteCnt < 8; byteCnt++){
if((byte >> byteCnt) & 1){
activeGridIndexes.push_back(activeGridIndex);
}
activeGridIndex++;
}
}
// LOG(INFO) << "activeGridIndexes.size(): " << activeGridIndexes.size();
return activeGridIndexes;
}
void StreamInfo::Forward(double lat, double lon, double h, double &x, double &y, double &z)
{
proj_->Forward(lat, lon, h, x, y, z);
}
void StreamInfo::parseBitmapBlock(
const BlockInfo& blockInfo,
const Internal::BlockDescribe &internalBlockDescribe)
{
float gridResolution = blockInfo.grid_resolution();
int32_t blockId = internalBlockDescribe.blockId;
int32_t blockIndexX = blockId / (int32_t)(1000 / BlockResolution);
int32_t blockIndexY = blockId % (int32_t)(1000 / BlockResolution);
float blockCenterX = ((float)blockIndexX + 0.5) * BlockResolution;
float blockCenterY = ((float)blockIndexY + 0.5) * BlockResolution;
vector<uint32_t> activeGridIndexes =
parseBitMap(blockInfo.bit_map(), blockInfo.bit_map_size());
for(size_t i = 0; i < activeGridIndexes.size(); i++){
auto index = activeGridIndexes[i];
auto grid_feature_index = blockInfo.grid_feature_index(i);
GridDistribution gridDistribution = Distributions_.grid_distribution(grid_feature_index);
uint32_t indexX = index / (uint32_t)(BlockResolution / gridResolution);
uint32_t indexY = index % (uint32_t)(BlockResolution / gridResolution);
size_t oneDistributionCnt = gridDistribution.one_distribution_size();
float centerX = ((float)indexX + 0.5) * gridResolution - BlockResolution / 2;
float centerY = ((float)indexY + 0.5) * gridResolution - BlockResolution / 2;
for(size_t i = 0; i < oneDistributionCnt; i++){
OneDistribution oneDistribution = gridDistribution.one_distribution(i);
for(int32_t j = 0;
j < oneDistribution.z_delta_leval();
j++){
int32_t indexZ = j + oneDistribution.floor();
pcl::PointXYZI point;
point.x = centerX + blockCenterX + offset_.x();
point.y = centerY + blockCenterY + offset_.y();
point.z = ((float)indexZ + 0.5) * ZResolution;
point.intensity = oneDistribution.intensity() * 8;
extractedPointcloud_->push_back(point);
}
}
}
}
void StreamInfo::parseIndexBlock(
const BlockInfo& blockInfo,
const Internal::BlockDescribe &internalBlockDescribe)
{
float gridResolution = blockInfo.grid_resolution();
int32_t blockId = internalBlockDescribe.blockId;
int32_t blockIndexX = blockId / (1000 / (int32_t)BlockResolution);
int32_t blockIndexY = blockId % (1000 / (int32_t)BlockResolution);
float blockCenterX = ((float)blockIndexX + 0.5) * BlockResolution;
float blockCenterY = ((float)blockIndexY + 0.5) * BlockResolution;
for(size_t i = 0; i < blockInfo.grid_feature_index_size(); i++){
auto grid_feature_index = blockInfo.grid_feature_index(i);
if(grid_feature_index == 0){
continue;
}
grid_feature_index--;
GridDistribution gridDistribution = Distributions_.grid_distribution(grid_feature_index);
uint32_t indexX = i / (BlockResolution / gridResolution);
uint32_t indexY = i % (uint32_t)(BlockResolution / gridResolution);
size_t oneDistributionCnt = gridDistribution.one_distribution_size();
float centerX = ((float)indexX + 0.5) * gridResolution - BlockResolution / 2;
float centerY = ((float)indexY + 0.5) * gridResolution - BlockResolution / 2;
for(size_t i = 0; i < oneDistributionCnt; i++){
OneDistribution oneDistribution = gridDistribution.one_distribution(i);
for(int32_t j = 0;
j < oneDistribution.z_delta_leval();
j++){
int32_t indexZ = j + oneDistribution.floor();
pcl::PointXYZI point;
point.x = centerX + blockCenterX + offset_.x();
point.y = centerY + blockCenterY + offset_.y();
point.z = ((float)indexZ + 0.5) * ZResolution;
point.intensity = oneDistribution.intensity() * 8;
extractedPointcloud_->push_back(point);
}
}
}
}
#ifndef STREAMINFO_H
#define STREAMINFO_H
#include "utils/basic_types.h"
#include "proto_pb/common/header.pb.h"
#include "proto_pb/block/block_index.pb.h"
#include "proto_pb/block/block_info.pb.h"
#include "proto_pb/distribution/distribution.pb.h"
#include "voxel/voxel.h"
#include <GeographicLib/LocalCartesian.hpp>
using namespace GeographicLib;
namespace Internal {
struct BlockDescribe{
int32_t blockId = 0;
uint32_t blockOffset = 0;
uint32_t blockSize = 0;
};
}
typedef ::google::protobuf::RepeatedField< ::google::protobuf::uint32 >
ProtoRepeatedUint32;
class StreamInfo
{
public:
StreamInfo(const string& streamPath);
void load();
void parseOneBlock(
const Internal::BlockDescribe &internalBlockDescribe);
vector<uint32_t> parseBitMap(
const ProtoRepeatedUint32& bitmap,
const uint32_t size);
void Forward(double lat, double lon, double h, double& x, double& y, double& z);
private:
void parseBitmapBlock(
const BlockInfo& blockInfo,
const Internal::BlockDescribe &internalBlockDescribe);
void parseIndexBlock(
const BlockInfo &blockInfo,
const Internal::BlockDescribe &internalBlockDescribe);
private:
string streamPath_;
uint16_t headerLength_;
Header header_;
BlockIndex blockIndex_;
vector<Internal::BlockDescribe> blockDescribeVec_;
Distributions Distributions_;
PointCloudXYZI::Ptr extractedPointcloud_;
Vector3f offset_ = Vector3f::Zero();
Voxel voxel_;
boost::shared_ptr<LocalCartesian> proj_;
};
#endif // STREAMINFO_H
add_library(utils SHARED basic_functions.cpp)
#include "basic_functions.h"
vector<pair<uint32_t, uint32_t>> getIndexPeriod(const uint32_t size,
const uint8_t threadCnt)
{
vector<pair<uint32_t, uint32_t>> ret;
uint32_t whole_frame_cnt = size;
uint32_t min_frame_cnt = whole_frame_cnt / threadCnt;
uint32_t max_frame_cnt = min_frame_cnt + 1;
uint8_t max_divide_cnt = whole_frame_cnt % threadCnt;
uint32_t start_index = 0, last_item_cnt = 0;
for(uint8_t thread_index = 0; thread_index < threadCnt; thread_index++){
uint32_t item_cnt;
if(thread_index < max_divide_cnt){
item_cnt = max_frame_cnt;
}else{
item_cnt = min_frame_cnt;
}
start_index += last_item_cnt;
ret.push_back(make_pair(start_index, item_cnt));
last_item_cnt = item_cnt;
}
return ret;
}
#ifndef BASIC_FUNCTIONS_H
#define BASIC_FUNCTIONS_H
#include "basic_types.h"
#include <chrono>
#include "pcl_point_type.h"
using namespace chrono;
template <typename T>
Eigen::Matrix<T, 3, 1> RotationQuaternionToEulerVector(
const Eigen::Quaternion<T>& quaternion) {
Eigen::Quaternion<T> n_q = quaternion.normalized();
// We choose the quaternion with positive 'w', i.e., the one with a smaller
// angle that represents this orientation.
if (n_q.w() < 0.) {
// Multiply by -1. http://eigen.tuxfamily.org/bz/show_bug.cgi?id=560
n_q.w() = -1. * n_q.w();
n_q.x() = -1. * n_q.x();
n_q.y() = -1. * n_q.y();
n_q.z() = -1. * n_q.z();
}
// We convert the normalized_quaternion(n_q) into a vector along the rotation
// axis with length of the rotation angle.
const T roll = atan2(2 * (n_q.w() * n_q.x() + n_q.y() * n_q.z()),
1 - 2 * (n_q.x() * n_q.x() + n_q.y() * n_q.y()));
const T pitch = asin(2 * (n_q.w() * n_q.y() - n_q.z() * n_q.x()));
const T yaw = atan2(2 * (n_q.w() * n_q.z() + n_q.x() * n_q.y()),
1 - 2 * (n_q.y() * n_q.y() + n_q.z() * n_q.z()));
return Eigen::Matrix<T, 3, 1>(roll, pitch, yaw);
}
vector<pair<uint32_t, uint32_t>> getIndexPeriod(const uint32_t size,
const uint8_t threadCnt = MAX_THREAD_CNT);
//template<typename ItemType>
//void periodProcessThreadFunc(const PointCloudExport::Ptr &Vector,
// pair<uint32_t, uint32_t> period,
// boost::function<void(const ItemType &)> processItemFunc)
//{
// vector<ItemType> tempOutputVec;
// uint32_t start_index = period.first;
// uint32_t index_cnt = period.second;
// uint32_t final_index = start_index + index_cnt;
// for(uint32_t index = start_index; index < final_index; index++){
// processItemFunc(Vector->at(index));
// }
//}
//template<typename ItemType>
//void multiThreadProcess(const PointCloudExport::Ptr &Vector,
// boost::function<void(const ItemType &)> processItemFunc)
//{
// auto start = system_clock::now();
// vector<pair<uint32_t, uint32_t>> indexPeriod = getIndexPeriod(Vector->size(),
// std::thread::hardware_concurrency());
// vector<ThreadPtr> threadVec;
// boost::mutex mutex;
// for(size_t thread_index = 0; thread_index < indexPeriod.size(); thread_index++){
// threadVec.emplace_back(
// ThreadPtr(new boost::thread(boost::bind(&periodProcessThreadFunc<ItemType>,
// Vector,
// indexPeriod[thread_index],
// processItemFunc))));
// }
// for(uint8_t thread_index = 0; thread_index < indexPeriod.size(); thread_index++){
// threadVec[thread_index]->join();
// threadVec[thread_index].reset();
// }
// auto end = system_clock::now();
// auto duration = duration_cast<milliseconds>(end - start);
// LOG(INFO) << "process take " << double(duration.count()) / 1000 << " seconds,"
// << " output size: " << Vector->size();
//}
template<typename ItemType>
void periodProcessThreadFunc(const vector<ItemType> *Vector,
pair<uint32_t, uint32_t> period,
boost::function<void(const ItemType &)> processItemFunc)
{
uint32_t start_index = period.first;
uint32_t index_cnt = period.second;
uint32_t final_index = start_index + index_cnt;
for(uint32_t index = start_index; index < final_index; index++){
processItemFunc(Vector->at(index));
}
}
template<typename ItemType>
void multiThreadProcess(const vector<ItemType> &Vector,
boost::function<void(const ItemType &)> processItemFunc)
{
auto start = system_clock::now();
vector<pair<uint32_t, uint32_t>> indexPeriod = getIndexPeriod(Vector.size(),
std::thread::hardware_concurrency());
vector<ThreadPtr> threadVec;
boost::mutex mutex;
for(size_t thread_index = 0; thread_index < indexPeriod.size(); thread_index++){
threadVec.emplace_back(
ThreadPtr(new boost::thread(boost::bind(&periodProcessThreadFunc<ItemType>,
&Vector,
indexPeriod[thread_index],
processItemFunc))));
}
for(uint8_t thread_index = 0; thread_index < indexPeriod.size(); thread_index++){
threadVec[thread_index]->join();
threadVec[thread_index].reset();
}
auto end = system_clock::now();
auto duration = duration_cast<milliseconds>(end - start);
LOG(INFO) << "process take " << double(duration.count()) / 1000 << " seconds,"
<< " output size: " << Vector.size();
}
template<typename ItemType>
void syncProcessThreadFunc(const vector<ItemType> *inputVector,
int32_t *currentIndex,
// boost::mutex *mutex,
boost::function<void(const ItemType &)> processItemFunc)
{
uint32_t size = inputVector->size();
int32_t index;
while(true){
{
// boost::unique_lock<boost::mutex> guard(*mutex);
index = ++(*currentIndex);
}
if((uint32_t)index >= size){
// LOG(INFO) << "index: " << index;
break;
}
processItemFunc(inputVector->at((uint32_t)index));
}
}
template<typename ItemType>
void syncProcess(const vector<ItemType> &inputVector,
boost::function<void(const ItemType &)> processItemFunc)
{
auto start = system_clock::now();
int32_t currentIndex = -1;
boost::mutex mutex;
vector<ThreadPtr> threadVec;
for(size_t thread_index = 0; thread_index < std::thread::hardware_concurrency(); thread_index++){
threadVec.emplace_back(
ThreadPtr(new boost::thread(boost::bind(&syncProcessThreadFunc<ItemType>,
&inputVector,
&currentIndex,
// &mutex,
processItemFunc))));
}
for(uint8_t thread_index = 0; thread_index < std::thread::hardware_concurrency(); thread_index++){
threadVec[thread_index]->join();
threadVec[thread_index].reset();
}
auto end = system_clock::now();
auto duration = duration_cast<milliseconds>(end - start);
LOG(INFO) << "process take " << double(duration.count()) / 1000 << " seconds";
}
#endif // BASIC_FUNCTIONS_H
#ifndef BASIC_TYPES_H
#define BASIC_TYPES_H
#pragma once
#include <boost/shared_ptr.hpp>
#include <eigen3/Eigen/Geometry>
#include "glog/logging.h"
#include <map>
#include <iomanip>
#include <pcl/io/pcd_io.h>
#include <thread>
#include <boost/make_shared.hpp>
using namespace std;
using namespace Eigen;
#define MAX_THREAD_CNT (48)
typedef boost::shared_ptr<boost::thread> ThreadPtr;
/////////// dispatch /////////////
const float BlockResolution = 18.;
const float GridResolution6cm = 0.06;
const float GridResolution24cm = 0.24;
const float ZResolution = 0.03;
enum GridType{
blockType,
gridType
};
struct OneDistribution_{
int32_t floor = 1;
uint32_t z_delta_level = 2;
uint32_t intensity = 3;
};
struct GridDistribution_{
vector<OneDistribution_> oneDistributions;
int64_t getScore(){
int64_t score = 0;
if(oneDistributions.size() == 0){
return 0;
}
score += oneDistributions.size() * 1e12;
for(const OneDistribution_& oneDistribution : oneDistributions){
score += oneDistribution.z_delta_level * 1e8;
score += oneDistribution.floor * 1e4;
score += oneDistribution.intensity;
}
return score;
}
};
struct BlockDistribution_{
vector<GridDistribution_> gridDistributions;
};
struct IndexDistribution{
GridDistribution_ gridDistribution_;
map<int32_t, vector<uint32_t>> index_;
};
struct BlockInfo_ {
uint32_t block_id;
float grid_resolution;
vector<uint8_t> bit_map;
vector<uint32_t> active_grid_feature_index;
vector<uint32_t> whole_grid_feature_index;
};
/////////// AbstractParser /////////////
enum LidarType
{
HesaiP40 = 0,
HesaiXT32
};
/////////// Trajectory /////////////
#include <fstream>
struct PPK_Raw_Info{
uint32_t gps_week;
double gps_sec, lat, lng, height,
roll, pitch, yaw;
};
struct NODE_Raw_Info{
uint32_t node_id;
double time, x, y, z, w, qx, qy, qz;
};
enum DevicePosition{
TopLidar = 0,
BackLidar = 1,
IMU = 2
};
struct TrajPoint{
double timestamp = 0;
uint32_t nodeId = 0;
Vector3d translation = Vector3d::Identity();
Quaterniond rotation = Quaterniond::Identity();
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
enum TrajType{
PPK,
NODE
};
/////////// MapTask /////////////
struct Time_Duration{
double start_sec;
double end_sec;
};
/////////// StrategyControl /////////////
enum Pointcloud_Source_Mode{
PCAP_MODE,
BAG_MODE,
PCAP_BAG_MODE
};
enum PointCloudSource{
PCAP,
BAG
};
enum Trajectory_Source_Mode{
NODE_MODE,
PPK_MODE,
PPK_UNDISORT_NODE_MAP_MODE
};
enum Filter_Mode{
DYNAMIC_REMOVE_MODE,
DIRECT_OUTPUT_MODE
};
struct StageInfo{
DevicePosition lidarPosition;
PointCloudSource pointcloudSource;
};
enum Strategy_Mode{
MESH,
PERIOD
};
enum Bag_Mode{
Disorted,
Undisorted
};
/////////// TaskServer /////////////
#define NODES_PER_SUBMAP (64)
#define SUBMAP_PACE (32)
struct TaskDescribe{
string task_prefix;
vector<vector<Time_Duration>> time_durations_vec;
vector<string> output_prefix_vec;
};
/////////// DynamicRemover /////////////
const double MISS_PER_HIT_PER_STAGE = 4;
#endif // BASIC_TYPES_H
//#pragma once
#define PCL_NO_PRECOMPILE
#ifndef PCL_POINT_TYPE_H
#define PCL_POINT_TYPE_H
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
namespace pcl {
struct PointInternal {
PCL_ADD_POINT4D
PCL_ADD_RGB
float intensity;
float ring;
float label = 0;
float distance;
double timestamp;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW // make sure our new allocators are aligned
} EIGEN_ALIGN16;
}//end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT(
pcl::PointInternal, (float, x, x)(float, y, y)(float, z, z)(float, rgb, rgb)
(float, intensity, intensity)(float, ring, ring)(float, label, label)
(float, distance, distance)(double, timestamp, timestamp))
typedef pcl::PointInternal Point;
typedef pcl::PointCloud<Point> PointCloud;
/////////////////////////////////////////////////////////////
///
///
namespace pcl {
struct PointRos {
PCL_ADD_POINT4D
float intensity;
float ring;
float label = 0;
float timestamp;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW // make sure our new allocators are aligned
} EIGEN_ALIGN16;
}//end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT(
pcl::PointRos, (float, x, x)(float, y, y)(float, z, z)
(float, intensity, intensity)(float, ring, ring)(float, label, label)
(float, timestamp, timestamp))
typedef pcl::PointRos PointRos;
typedef pcl::PointCloud<PointRos> PointCloudRos;
/////////////////////////////////////////////////////////////
///
///
namespace pcl {
struct PointExport {
PCL_ADD_POINT4D
PCL_ADD_RGB
float intensity = 0;
float label = 0;
float info = 0;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW // make sure our new allocators are aligned
} EIGEN_ALIGN16;
}//end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT(
pcl::PointExport, (float, x, x)(float, y, y)(float, z, z)(float, rgb, rgb)
(float, intensity, intensity)(float, label, label)(float, info, info))
typedef pcl::PointExport PointExport;
typedef pcl::PointCloud<PointExport> PointCloudExport;
/////////////////////////////////////////////////////////////
namespace pcl {
struct PointLabel {
PCL_ADD_POINT4D
float intensity;
float trainLabel = 0;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW // make sure our new allocators are aligned
} EIGEN_ALIGN16;
}//end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT(
pcl::PointLabel, (float, x, x)(float, y, y)(float, z, z)
(float, intensity, intensity)(float, trainLabel, trainLabel))
typedef pcl::PointLabel PointLabel;
typedef pcl::PointCloud<PointLabel> PointCloudLabel;
#endif // PCL_POINT_TYPE_H
#ifndef SYNCHRONIZEDQUEUE_H
#define SYNCHRONIZEDQUEUE_H
#endif // SYNCHRONIZEDQUEUE_H
#include <boost/thread/thread.hpp>
#include <boost/asio.hpp>
#include <queue>
#include <deque>
#pragma once
template<typename T>
class SynchronizedQueue
{
public:
SynchronizedQueue () :
queue_(), mutex_(), cond_(), request_to_end_(false), enqueue_data_(true) { }
void
enqueue (const T& data)
{
boost::unique_lock<boost::mutex> lock (mutex_);
if (enqueue_data_)
{
queue_.push (data);
cond_.notify_one ();
}
}
bool
dequeue (T& result)
{
boost::unique_lock<boost::mutex> lock (mutex_);
while (queue_.empty () && (!request_to_end_))
{
cond_.wait (lock);
}
if (request_to_end_)
{
doEndActions ();
return false;
}
result = queue_.front ();
queue_.pop ();
return true;
}
void
stopQueue ()
{
boost::unique_lock<boost::mutex> lock (mutex_);
request_to_end_ = true;
cond_.notify_all ();
}
unsigned int
size ()
{
boost::unique_lock<boost::mutex> lock (mutex_);
return static_cast<unsigned int> (queue_.size ());
}
bool
isEmpty () const
{
boost::unique_lock<boost::mutex> lock (mutex_);
return (queue_.empty ());
}
private:
void
doEndActions ()
{
enqueue_data_ = false;
while (!queue_.empty ())
{
queue_.pop ();
}
}
std::queue<T> queue_; // Use STL queue to store data
mutable boost::mutex mutex_; // The mutex to synchronise on
boost::condition_variable cond_; // The condition to wait for
bool request_to_end_;
bool enqueue_data_;
};
#ifndef SYS_UTILS_H
#define SYS_UTILS_H
#include <sys/resource.h>
const char data_mem[] = "VmRSS:";
void print_mem(int pid)
{
FILE *stream;
char cache[256];
char mem_info[64];
sprintf(mem_info, "/proc/%d/status", pid);
stream = fopen(mem_info, "r");
if (stream == NULL) {
return;
}
while(fscanf(stream, "%s", cache) != EOF) {
if (strncmp(cache, data_mem, sizeof(data_mem)) == 0) {
if (fscanf(stream, "%s", cache) != EOF) {
LOG(INFO) << "current memory: " << string(cache);
break;
}
}
}
}
int SysMem()
{
const int MAX_LEN=1024;
char sInfo[MAX_LEN];
char strInfo[1024];
//
long mem_used = -1;
long mem_free = -1;
long mem_total = -1;
char name[20];
float fMemRate;
FILE *fp;
char buf1[128];
char buf2[128];
int i = 0;
memset(sInfo, 0x00, sizeof(sInfo));
memset(strInfo, 0x00, sizeof(strInfo));
//读取文件中mem信息
fp = fopen("/proc/meminfo","r");
if(fp == NULL)
{
perror("fopen:");
return -1;
}
fgets(buf1,sizeof(buf1),fp);
fgets(buf2,sizeof(buf2),fp);
fclose(fp);
//计算
strcpy(strInfo," RTOL(kb) FREE(kb) RINUSE(kb) RATE%%\n\n");
sscanf(buf1,"%s%ld",name,&mem_total);
sscanf(buf2,"%s%ld",name,&mem_free);
mem_used = mem_total - mem_free;
fMemRate = 1.0 * mem_used / mem_total;
sprintf(sInfo,"% 6ld %6ld %6ld %6.1f\n",mem_total,mem_free,mem_used,fMemRate);
strcat(strInfo,sInfo);
// printf("%s\n",strInfo);
return mem_total;
}
#endif // SYS_UTILS_H
add_library(voxel SHARED voxel.cpp)
target_link_libraries(voxel
${Boost_LIBRARIES}
${PCL_LIBRARIES})
This diff is collapsed.
#include "voxel.h"
Voxel::Voxel()
:voxel_size_(GridResolution6cm * 2),
voxels_(voxel_size_)
{
}
void Voxel::calculateHits(
const PointCloudXYZI::Ptr &frames){
PointCloudXYZI checked_frame;
for(const auto &point : *frames){
Eigen::Vector3d pt(point.x, point.y, point.z);
const Eigen::Array3i index = voxels_.GetCellIndex(pt);
while(!checkIndex(index)){
voxels_.Grow(index);
}
VoxelData *voxel;
if(!voxels_.mutable_value(index, voxel)){
LOG(WARNING) << "mutable_value fail!";
continue;
}
if(voxel == nullptr){
LOG(WARNING) << "voxel == nullptr!";
continue;
}
const GridDivision grid_quadrant = getGridDivision(index, pt);
if (grid_quadrant == GridDivision::None){
LOG(WARNING) << "In Voxel filter, Grid Division is ERROR, Please check";
}else{
// LOG(INFO) << "voxel->grid_value: " << voxel->grid_value;
// LOG(INFO) << "grid_quadrant: " << (int32_t)grid_quadrant;
if (voxel->grid_value != 0xff){
if(!voxel->check(grid_quadrant)){
voxel->set(grid_quadrant);
checked_frame.push_back(point);
}
}
voxel->hits++;
}
}
}
bool Voxel::checkIndex(const Array3i &index)
{
return voxels_.checkIndex(index);
}
Voxel::GridDivision Voxel::getGridDivision(
const Eigen::Array3i& index, const Eigen::Vector3d& position) {
bool x_sig = ((position[0] - index[0] * voxel_size_) >= 0);
bool y_sig = ((position[1] - index[1] * voxel_size_) >= 0);
bool z_sig = ((position[2] - index[2] * voxel_size_) >= 0);
if (x_sig && y_sig && z_sig) {
return GridDivision::Quadrant_0;
} else if (!x_sig && y_sig && z_sig) {
return GridDivision::Quadrant_1;
} else if (!x_sig && !y_sig && z_sig) {
return GridDivision::Quadrant_2;
} else if ( x_sig && !y_sig && z_sig) {
return GridDivision::Quadrant_3;
} else if ( x_sig && y_sig && !z_sig) {
return GridDivision::Quadrant_4;
} else if (!x_sig && y_sig && !z_sig) {
return GridDivision::Quadrant_5;
} else if (!x_sig && !y_sig && !z_sig) {
return GridDivision::Quadrant_6;
} else if ( x_sig && !y_sig && !z_sig) {
return GridDivision::Quadrant_7;
}
return GridDivision::None;
}
#ifndef VOXEL_H
#define VOXEL_H
#include "utils/basic_types.h"
#include "hybrid_grid.h"
typedef pcl::PointCloud<pcl::PointXYZI> PointCloudXYZI;
class Voxel
{
enum class GridDivision;
public:
Voxel();
void calculateHits(
const PointCloudXYZI::Ptr &frames);
private:
bool checkIndex(const Array3i &index);
GridDivision getGridDivision(
const Eigen::Array3i &index,
const Eigen::Vector3d &position);
private:
enum class GridDivision {
Quadrant_0 = 0,
Quadrant_1 = 1,
Quadrant_2 = 2,
Quadrant_3 = 3,
Quadrant_4 = 4,
Quadrant_5 = 5,
Quadrant_6 = 6,
Quadrant_7 = 7,
None
};
struct VoxelData {
VoxelData() : hits(0), rays(0), grid_value(0) {
}
uint32_t hits : 24;
uint32_t grid_value : 8;
uint32_t rays : 24;
uint32_t trajMask : 8;
float label = 0;
// float rgb = 0;
void updateTrajMask(int traj){
trajMask |= 1 << (traj - 1);
}
bool operator==(const VoxelData voxel_data) const
{
return hits == voxel_data.hits && rays == voxel_data.rays &&
grid_value == voxel_data.grid_value;
}
VoxelData operator=(const VoxelData& voxel_data) {
hits = voxel_data.hits;
rays = voxel_data.rays;
grid_value = voxel_data.grid_value;
return *this;
}
bool check(const GridDivision grid_quadrant) const {
switch (grid_quadrant) {
case GridDivision::Quadrant_0:
return (grid_value & 0x01) > 0;
case GridDivision::Quadrant_1:
return (grid_value & 0x02) > 0;
case GridDivision::Quadrant_2:
return (grid_value & 0x04) > 0;
case GridDivision::Quadrant_3:
return (grid_value & 0x08) > 0;
case GridDivision::Quadrant_4:
return (grid_value & 0x10) > 0;
case GridDivision::Quadrant_5:
return (grid_value & 0x20) > 0;
case GridDivision::Quadrant_6:
return (grid_value & 0x40) > 0;
case GridDivision::Quadrant_7:
return (grid_value & 0x80) > 0;
case GridDivision::None:
return false;
}
return false;
}
void set(const GridDivision grid_quadrant) {
switch (grid_quadrant) {
case GridDivision::Quadrant_0:
grid_value |= 0x01;
break;
case GridDivision::Quadrant_1:
grid_value |= 0x02;
break;
case GridDivision::Quadrant_2:
grid_value |= 0x04;
break;
case GridDivision::Quadrant_3:
grid_value |= 0x08;
break;
case GridDivision::Quadrant_4:
grid_value |= 0x10;
break;
case GridDivision::Quadrant_5:
grid_value |= 0x20;
break;
case GridDivision::Quadrant_6:
grid_value |= 0x40;
break;
case GridDivision::Quadrant_7:
grid_value |= 0x80;
break;
case GridDivision::None:
return;
}
}
unsigned int getQuadrant(const GridDivision grid_quadrant) const {
switch (grid_quadrant) {
case GridDivision::Quadrant_0:
return 0;
case GridDivision::Quadrant_1:
return 1;
case GridDivision::Quadrant_2:
return 2;
case GridDivision::Quadrant_3:
return 3;
case GridDivision::Quadrant_4:
return 4;
case GridDivision::Quadrant_5:
return 5;
case GridDivision::Quadrant_6:
return 6;
case GridDivision::Quadrant_7:
return 7;
case GridDivision::None:
return 0;
}
return 0;
}
};
const double voxel_size_;
HybridGridBase<VoxelData> voxels_;
};
#endif // VOXEL_H
find_package(Protobuf 3 REQUIRED)
#设置输出路径
set(MESSAGE_DIR ${CMAKE_SOURCE_DIR}/proto_pb)
if(EXISTS "${MESSAGE_DIR}" AND IS_DIRECTORY "${MESSAGE_DIR}")
SET(DST_DIR ${MESSAGE_DIR})
else()
file(MAKE_DIRECTORY ${MESSAGE_DIR})
SET(DST_DIR ${MESSAGE_DIR})
endif()
#设置protoc的搜索路径
LIST(APPEND PROTO_FLAGS -I${CMAKE_SOURCE_DIR}/proto)
#获取需要编译的proto文件
file(GLOB_RECURSE MSG_PROTOS ${CMAKE_SOURCE_DIR}/proto/*/*.proto)
set(MESSAGE_SRC "")
set(MESSAGE_HDRS "")
foreach(msg ${MSG_PROTOS})
get_filename_component(FIL_WE ${msg} NAME_WE)
# 生成源码
execute_process(
COMMAND ${PROTOBUF_PROTOC_EXECUTABLE} ${PROTO_FLAGS} --cpp_out=${DST_DIR} ${msg}
)
endforeach()
file(GLOB_RECURSE PROTO_PB_SRC ${DST_DIR}/*.cc)
include_directories(${DST_DIR})
add_library(proto_pb ${PROTO_PB_SRC})
target_link_libraries(proto_pb
protobuf)
syntax = "proto3";
message BlockDescribe{
int32 block_id = 1;
uint32 block_info_offset = 2;
}
message BlockIndex{
float local_offset_x = 1;
float local_offset_y = 2;
float local_offset_z = 3;
repeated BlockDescribe block_describe = 4;
}
syntax = "proto3";
message BlockInfo {
float grid_resolution = 1;
repeated uint32 bit_map = 2;
repeated uint32 grid_feature_index = 3;
}
syntax = "proto3";
message Header {
uint32 mesh_level = 1;
fixed32 mesh_id = 2;
fixed32 longtitude = 3;
fixed32 latitude = 4;
float height = 5;
float offset_x = 6;
float offset_y = 7;
float offset_z = 8;
uint32 active_block_count = 9;
uint32 max_block_count = 10;
float block_relolution = 11;
float grid_relolution = 12;
uint32 block_index_length = 13;
uint32 block_info_length = 14;
enum SaveType {
DIRECT = 0;
BIT = 1;
}
SaveType save_type = 15;
}
syntax = "proto3";
message OneDistribution{
sint32 floor = 1;
uint32 z_delta_leval = 2;
uint32 intensity = 3;
}
message GridDistribution{
repeated OneDistribution one_distribution = 1;
}
message Distributions{
repeated GridDistribution grid_distribution = 1;
}
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
// Generated by the protocol buffer compiler. DO NOT EDIT!
// source: block/block_info.proto
#ifndef PROTOBUF_block_2fblock_5finfo_2eproto__INCLUDED
#define PROTOBUF_block_2fblock_5finfo_2eproto__INCLUDED
#include <string>
#include <google/protobuf/stubs/common.h>
#if GOOGLE_PROTOBUF_VERSION < 3000000
#error This file was generated by a newer version of protoc which is
#error incompatible with your Protocol Buffer headers. Please update
#error your headers.
#endif
#if 3000000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
#error This file was generated by an older version of protoc which is
#error incompatible with your Protocol Buffer headers. Please
#error regenerate this file with a newer version of protoc.
#endif
#include <google/protobuf/arena.h>
#include <google/protobuf/arenastring.h>
#include <google/protobuf/generated_message_util.h>
#include <google/protobuf/metadata.h>
#include <google/protobuf/message.h>
#include <google/protobuf/repeated_field.h>
#include <google/protobuf/extension_set.h>
#include <google/protobuf/unknown_field_set.h>
// @@protoc_insertion_point(includes)
// Internal implementation detail -- do not call these.
void protobuf_AddDesc_block_2fblock_5finfo_2eproto();
void protobuf_AssignDesc_block_2fblock_5finfo_2eproto();
void protobuf_ShutdownFile_block_2fblock_5finfo_2eproto();
class BlockInfo;
// ===================================================================
class BlockInfo : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:BlockInfo) */ {
public:
BlockInfo();
virtual ~BlockInfo();
BlockInfo(const BlockInfo& from);
inline BlockInfo& operator=(const BlockInfo& from) {
CopyFrom(from);
return *this;
}
static const ::google::protobuf::Descriptor* descriptor();
static const BlockInfo& default_instance();
void Swap(BlockInfo* other);
// implements Message ----------------------------------------------
inline BlockInfo* New() const { return New(NULL); }
BlockInfo* New(::google::protobuf::Arena* arena) const;
void CopyFrom(const ::google::protobuf::Message& from);
void MergeFrom(const ::google::protobuf::Message& from);
void CopyFrom(const BlockInfo& from);
void MergeFrom(const BlockInfo& from);
void Clear();
bool IsInitialized() const;
int ByteSize() const;
bool MergePartialFromCodedStream(
::google::protobuf::io::CodedInputStream* input);
void SerializeWithCachedSizes(
::google::protobuf::io::CodedOutputStream* output) const;
::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray(
bool deterministic, ::google::protobuf::uint8* output) const;
::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const {
return InternalSerializeWithCachedSizesToArray(false, output);
}
int GetCachedSize() const { return _cached_size_; }
private:
void SharedCtor();
void SharedDtor();
void SetCachedSize(int size) const;
void InternalSwap(BlockInfo* other);
private:
inline ::google::protobuf::Arena* GetArenaNoVirtual() const {
return _internal_metadata_.arena();
}
inline void* MaybeArenaPtr() const {
return _internal_metadata_.raw_arena_ptr();
}
public:
::google::protobuf::Metadata GetMetadata() const;
// nested types ----------------------------------------------------
// accessors -------------------------------------------------------
// optional float grid_resolution = 1;
void clear_grid_resolution();
static const int kGridResolutionFieldNumber = 1;
float grid_resolution() const;
void set_grid_resolution(float value);
// repeated uint32 bit_map = 2;
int bit_map_size() const;
void clear_bit_map();
static const int kBitMapFieldNumber = 2;
::google::protobuf::uint32 bit_map(int index) const;
void set_bit_map(int index, ::google::protobuf::uint32 value);
void add_bit_map(::google::protobuf::uint32 value);
const ::google::protobuf::RepeatedField< ::google::protobuf::uint32 >&
bit_map() const;
::google::protobuf::RepeatedField< ::google::protobuf::uint32 >*
mutable_bit_map();
// repeated uint32 grid_feature_index = 3;
int grid_feature_index_size() const;
void clear_grid_feature_index();
static const int kGridFeatureIndexFieldNumber = 3;
::google::protobuf::uint32 grid_feature_index(int index) const;
void set_grid_feature_index(int index, ::google::protobuf::uint32 value);
void add_grid_feature_index(::google::protobuf::uint32 value);
const ::google::protobuf::RepeatedField< ::google::protobuf::uint32 >&
grid_feature_index() const;
::google::protobuf::RepeatedField< ::google::protobuf::uint32 >*
mutable_grid_feature_index();
// @@protoc_insertion_point(class_scope:BlockInfo)
private:
::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_;
bool _is_default_instance_;
::google::protobuf::RepeatedField< ::google::protobuf::uint32 > bit_map_;
mutable int _bit_map_cached_byte_size_;
::google::protobuf::RepeatedField< ::google::protobuf::uint32 > grid_feature_index_;
mutable int _grid_feature_index_cached_byte_size_;
float grid_resolution_;
mutable int _cached_size_;
friend void protobuf_AddDesc_block_2fblock_5finfo_2eproto();
friend void protobuf_AssignDesc_block_2fblock_5finfo_2eproto();
friend void protobuf_ShutdownFile_block_2fblock_5finfo_2eproto();
void InitAsDefaultInstance();
static BlockInfo* default_instance_;
};
// ===================================================================
// ===================================================================
#if !PROTOBUF_INLINE_NOT_IN_HEADERS
// BlockInfo
// optional float grid_resolution = 1;
inline void BlockInfo::clear_grid_resolution() {
grid_resolution_ = 0;
}
inline float BlockInfo::grid_resolution() const {
// @@protoc_insertion_point(field_get:BlockInfo.grid_resolution)
return grid_resolution_;
}
inline void BlockInfo::set_grid_resolution(float value) {
grid_resolution_ = value;
// @@protoc_insertion_point(field_set:BlockInfo.grid_resolution)
}
// repeated uint32 bit_map = 2;
inline int BlockInfo::bit_map_size() const {
return bit_map_.size();
}
inline void BlockInfo::clear_bit_map() {
bit_map_.Clear();
}
inline ::google::protobuf::uint32 BlockInfo::bit_map(int index) const {
// @@protoc_insertion_point(field_get:BlockInfo.bit_map)
return bit_map_.Get(index);
}
inline void BlockInfo::set_bit_map(int index, ::google::protobuf::uint32 value) {
bit_map_.Set(index, value);
// @@protoc_insertion_point(field_set:BlockInfo.bit_map)
}
inline void BlockInfo::add_bit_map(::google::protobuf::uint32 value) {
bit_map_.Add(value);
// @@protoc_insertion_point(field_add:BlockInfo.bit_map)
}
inline const ::google::protobuf::RepeatedField< ::google::protobuf::uint32 >&
BlockInfo::bit_map() const {
// @@protoc_insertion_point(field_list:BlockInfo.bit_map)
return bit_map_;
}
inline ::google::protobuf::RepeatedField< ::google::protobuf::uint32 >*
BlockInfo::mutable_bit_map() {
// @@protoc_insertion_point(field_mutable_list:BlockInfo.bit_map)
return &bit_map_;
}
// repeated uint32 grid_feature_index = 3;
inline int BlockInfo::grid_feature_index_size() const {
return grid_feature_index_.size();
}
inline void BlockInfo::clear_grid_feature_index() {
grid_feature_index_.Clear();
}
inline ::google::protobuf::uint32 BlockInfo::grid_feature_index(int index) const {
// @@protoc_insertion_point(field_get:BlockInfo.grid_feature_index)
return grid_feature_index_.Get(index);
}
inline void BlockInfo::set_grid_feature_index(int index, ::google::protobuf::uint32 value) {
grid_feature_index_.Set(index, value);
// @@protoc_insertion_point(field_set:BlockInfo.grid_feature_index)
}
inline void BlockInfo::add_grid_feature_index(::google::protobuf::uint32 value) {
grid_feature_index_.Add(value);
// @@protoc_insertion_point(field_add:BlockInfo.grid_feature_index)
}
inline const ::google::protobuf::RepeatedField< ::google::protobuf::uint32 >&
BlockInfo::grid_feature_index() const {
// @@protoc_insertion_point(field_list:BlockInfo.grid_feature_index)
return grid_feature_index_;
}
inline ::google::protobuf::RepeatedField< ::google::protobuf::uint32 >*
BlockInfo::mutable_grid_feature_index() {
// @@protoc_insertion_point(field_mutable_list:BlockInfo.grid_feature_index)
return &grid_feature_index_;
}
#endif // !PROTOBUF_INLINE_NOT_IN_HEADERS
// @@protoc_insertion_point(namespace_scope)
// @@protoc_insertion_point(global_scope)
#endif // PROTOBUF_block_2fblock_5finfo_2eproto__INCLUDED
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment