blam icon indicating copy to clipboard operation
blam copied to clipboard

blam_slam running error

Open junliu111 opened this issue 6 years ago • 5 comments

after running the demo code roslaunch blam_example test_online.launch, it shows the following error. I have source the internal/devel.zsh file.

The system is ubuntu: 18.04.1, ros: melodic.

SUMMARY

PARAMETERS

  • /blam/blam_slam/check_for_loop_closures: True
  • /blam/blam_slam/filtering/decimate_percentage: 0.9
  • /blam/blam_slam/filtering/grid_filter: True
  • /blam/blam_slam/filtering/grid_res: 0.2
  • /blam/blam_slam/filtering/outlier_filter: False
  • /blam/blam_slam/filtering/outlier_knn: 10
  • /blam/blam_slam/filtering/outlier_std: 1.0
  • /blam/blam_slam/filtering/radius: 0.15
  • /blam/blam_slam/filtering/radius_filter: False
  • /blam/blam_slam/filtering/radius_knn: 3
  • /blam/blam_slam/filtering/random_filter: True
  • /blam/blam_slam/frame_id/base: base
  • /blam/blam_slam/frame_id/fixed: world
  • /blam/blam_slam/frame_id/odometry: odometry
  • /blam/blam_slam/icp/corr_dist: 2.0
  • /blam/blam_slam/icp/iterations: 10
  • /blam/blam_slam/icp/max_rotation: 0.1
  • /blam/blam_slam/icp/max_translation: 0.09
  • /blam/blam_slam/icp/tf_epsilon: 1e-10
  • /blam/blam_slam/icp/transform_thresholding: False
  • /blam/blam_slam/init/orientation/pitch: 0.0
  • /blam/blam_slam/init/orientation/roll: 0.0
  • /blam/blam_slam/init/orientation/yaw: 0.0
  • /blam/blam_slam/init/orientation_sigma/pitch: 0.02
  • /blam/blam_slam/init/orientation_sigma/roll: 0.02
  • /blam/blam_slam/init/orientation_sigma/yaw: 0.02
  • /blam/blam_slam/init/position/x: 0.0
  • /blam/blam_slam/init/position/y: 0.0
  • /blam/blam_slam/init/position/z: 0.0
  • /blam/blam_slam/init/position_sigma/x: 0.1
  • /blam/blam_slam/init/position_sigma/y: 0.1
  • /blam/blam_slam/init/position_sigma/z: 0.1
  • /blam/blam_slam/localization/corr_dist: 1.0
  • /blam/blam_slam/localization/iterations: 10
  • /blam/blam_slam/localization/max_rotation: 0.1
  • /blam/blam_slam/localization/max_translation: 0.05
  • /blam/blam_slam/localization/tf_epsilon: 1e-10
  • /blam/blam_slam/localization/transform_thresholding: False
  • /blam/blam_slam/map/octree_resolution: 0.05
  • /blam/blam_slam/max_tolerable_fitness: 0.15
  • /blam/blam_slam/poses_before_reclosing: 40
  • /blam/blam_slam/proximity_threshold: 1.5
  • /blam/blam_slam/rate/estimate: 20.0
  • /blam/blam_slam/rate/visualization: 0.5
  • /blam/blam_slam/relinearize_skip: 1
  • /blam/blam_slam/relinearize_threshold: 0.01
  • /blam/blam_slam/skip_recent_poses: 40
  • /blam/blam_slam/translation_threshold: 0.5
  • /blam/blam_slam/visualizer/enable_visualization: False
  • /rosdistro: melodic
  • /rosversion: 1.14.3
  • /use_sim_time: False

NODES /blam/ blam_slam (blam_slam/blam_slam_node)

ROS_MASTER_URI=http://localhost:11311

process[blam/blam_slam-1]: started with pid [26609] [ INFO] [1541090716.155156906]: /blam/blam_slam/BlamSlam: Registering online callbacks. blam_slam_node: /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. [blam/blam_slam-1] process has died [pid 26609, exit code -6, cmd /home/jun/catkin_ws/src/blam/internal/devel/lib/blam_slam/blam_slam_node ~pcld:=/velodyne_points __name:=blam_slam __log:=/home/jun/.ros/log/4cd720f2-ddec-11e8-bc37-e4a7a0130394/blam-blam_slam-1.log]. log file: /home/jun/.ros/log/4cd720f2-ddec-11e8-bc37-e4a7a0130394/blam-blam_slam-1*.log all processes on machine have died, roslaunch will exit shutting down processing monitor... ... shutting down processing monitor complete done

Anyone has any idea about how could this happen? Thanks.

junliu111 avatar Nov 01 '18 16:11 junliu111

I have the same issue on ubuntu 18.04 using melodic...

thorstink avatar Nov 22 '18 19:11 thorstink

I am also encountering this issue on 18.04 / melodic using bslam_offline

aj-n avatar Dec 10 '18 22:12 aj-n

Same problem here with both online and offline. Is there anyone that was able to solve it?

uzdry avatar Jan 06 '19 20:01 uzdry

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)) {

nevermoredanny avatar Feb 11 '19 14:02 nevermoredanny

Thanks, it works well

vahidbehtajisiahkal avatar Feb 14 '19 08:02 vahidbehtajisiahkal