Livox_automatic_calibration icon indicating copy to clipboard operation
Livox_automatic_calibration copied to clipboard

Error in local map building

Open ziyou1987912 opened this issue 4 years ago • 6 comments

Start building local map... Loaded 1182 frames from Base-LiDAR mapping: /build/pcl-OilVEB/pcl-1.8.1+dfsg1/octree/include/pcl/octree/impl/octree_pointcloud.hpp:688: void pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>::genOctreeKeyforPoint(const PointT&, pcl::octree::OctreeKey&) const [with PointT = pcl::PointXYZ; LeafContainerT = pcl::octree::OctreeContainerPointIndices; BranchContainerT = pcl::octree::OctreeContainerEmpty; OctreeT = pcl::octree::OctreeBase<pcl::octree::OctreeContainerPointIndices, pcl::octree::OctreeContainerEmpty>]: Assertion `key_arg.x <= this->max_key_.x' failed. Aborted (core dumped)

ziyou1987912 avatar Jul 04 '20 04:07 ziyou1987912

PointCloudMapper.cc change

if (!map_octree_->isVoxelOccupiedAtPoint(p)) {

to:

double min_x, min_y, min_z, max_x, max_y, max_z; map_octree_->getBoundingBox(min_x, min_y, min_z, max_x, max_y, max_z); bool isInBox = (p.x >= min_x && p.x <= max_x) && (p.y >= min_y && p.y <= max_y) && (p.z >= min_z && p.z <= max_z);

if (!isInBox || !map_octree_->isVoxelOccupiedAtPoint(p)) {

Livox-SDK avatar Jul 07 '20 05:07 Livox-SDK

Start building local map... Loaded 1182 frames from Base-LiDAR 100% [||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||] Saving submap... Mapping done! Start calibration... Reading H-LiDAR map data... Loaded 1084894 data points from H_LiDAR_Map.pcd calibration: /build/pcl-OilVEB/pcl-1.8.1+dfsg1/octree/include/pcl/octree/impl/octree_pointcloud.hpp:688: void pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>::genOctreeKeyforPoint(const PointT&, pcl::octree::OctreeKey&) const [with PointT = pcl::PointXYZ; LeafContainerT = pcl::octree::OctreeContainerPointIndices; BranchContainerT = pcl::octree::OctreeContainerEmpty; OctreeT = pcl::octree::OctreeBase<pcl::octree::OctreeContainerPointIndices, pcl::octree::OctreeContainerEmpty>]: Assertion `key_arg.x <= this->max_key_.x' failed. Aborted (core dumped)

ziyou1987912 avatar Jul 09 '20 10:07 ziyou1987912

There is another PointCloudMapper.cc in calibration file, please check

Livox-SDK avatar Jul 20 '20 04:07 Livox-SDK

There is another PointCloudMapper.cc in calibration file, please check

I have modified the file in calibration and mapping,while I still get an error like that.Can you tell me how to solve this problem?Thanks.

Start building local map... Loaded 1182 frames from Base-LiDAR 100% [||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||] Saving submap... terminate called after throwing an instance of 'pcl::IOException' what(): : [pcl::PCDWriter::writeASCII] Could not open file for writing! Aborted (core dumped) Start calibration... Reading H-LiDAR map data... [pcl::PCDReader::readHeader] Could not find file '../data/H-LiDAR-Map-data/H_LiDAR_Map.pcd'. Couldn't read H_LiDAR_Map

757628 avatar Jul 23 '20 02:07 757628

There is another PointCloudMapper.cc in calibration file, please check

I have modified the file in calibration and mapping,while I still get an error like that.Can you tell me how to solve this problem?Thanks.

Start building local map... Loaded 1182 frames from Base-LiDAR 100% [||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||] Saving submap... terminate called after throwing an instance of 'pcl::IOException' what(): : [pcl::PCDWriter::writeASCII] Could not open file for writing! Aborted (core dumped) Start calibration... Reading H-LiDAR map data... [pcl::PCDReader::readHeader] Could not find file '../data/H-LiDAR-Map-data/H_LiDAR_Map.pcd'. Couldn't read H_LiDAR_Map

create a dir named "H_LiDAR_Map"

wxjiang avatar Jul 29 '20 22:07 wxjiang

Start building local map... Loaded 1182 frames from Base-LiDAR 100% [||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||] Saving submap... Mapping done! Start calibration... Reading H-LiDAR map data... Loaded 1084894 data points from H_LiDAR_Map.pcd calibration: /build/pcl-OilVEB/pcl-1.8.1+dfsg1/octree/include/pcl/octree/impl/octree_pointcloud.hpp:688: void pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>::genOctreeKeyforPoint(const PointT&, pcl::octree::OctreeKey&) const [with PointT = pcl::PointXYZ; LeafContainerT = pcl::octree::OctreeContainerPointIndices; BranchContainerT = pcl::octree::OctreeContainerEmpty; OctreeT = pcl::octree::OctreeBase<pcl::octree::OctreeContainerPointIndices, pcl::octree::OctreeContainerEmpty>]: Assertion `key_arg.x <= this->max_key_.x' failed. Aborted (core dumped)

this is a same problem , you can change the code in /calibration/PointCloudMapper.cpp in function bool PointCloudMapper::InsertPoints(const PointCloud::ConstPtr& points, PointCloud* incremental_points)

callmebylxh avatar Mar 18 '21 06:03 callmebylxh