Closed Nothand0212 closed 1 year ago
Could you check the input of the sensor height estimation module? What platforms do you use? In cases of automobiles, sometimes fine-tuning is required.
Could you check the input of the sensor height estimation module? What platforms do you use? In cases of automobiles, sometimes fine-tuning is required.
did you mean that parameter 'Sensor Height' in params.yaml? Dost it need a precise value? because in my work which is on boat, the height from water face to laser sensor will change a little.
My platforms : Ubuntu 20.04, ROS Noetic
I use gdb check the error. It tells error is about Eigen.
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
[New Thread 0x7ffff3322700 (LWP 617513)]
[New Thread 0x7ffff2b21700 (LWP 617514)]
[New Thread 0x7ffff2320700 (LWP 617515)]
[New Thread 0x7ffff1b1f700 (LWP 617516)]
[ INFO] [1683770191.875773722]: Inititalizing PatchWork...
Global thr. is not in use
[ INFO] [1683770191.878789986]: Sensor Height: 2.500000
[ INFO] [1683770191.878796261]: Num of Iteration: 3
[ INFO] [1683770191.878801150]: Num of LPR: 20
[ INFO] [1683770191.878805695]: Num of min. points: 10
[ INFO] [1683770191.878810529]: Seeds Threshold: 0.500000
[ INFO] [1683770191.878815144]: Distance Threshold: 0.125000
[ INFO] [1683770191.878820305]: Max. range:: 80.000000
[ INFO] [1683770191.878824690]: Min. range:: 2.700000
[ INFO] [1683770191.878829233]: Num. rings: 16
[ INFO] [1683770191.878833548]: Num. sectors: 54
[ INFO] [1683770191.878838588]: adaptive_seed_selection_margin: -1.100000
[ INFO] [1683770191.879345830]: Uprightness threshold: 0.707000
[ INFO] [1683770191.879351874]: Elevation thresholds: 0.523000 0.746000 0.879000 1.125000
[ INFO] [1683770191.879357327]: Flatness thresholds: 0.000500 0.000725 0.001000 0.001000
[ INFO] [1683770191.879364911]: Num. zones: 4
INITIALIZATION COMPLETE
80859th node come
Failed to find match for field 'label'.
Failed to find match for field 'id'.
Operating patchwork...
--Type <RET> for more, q to quit, c to continue without paging--c
Thread 1 "ros_kitti" received signal SIGSEGV, Segmentation fault.
0x000055555573fb54 in Eigen::internal::coeff_visitor<Eigen::Matrix<double, 1, -1, 1, 1, -1> >::init (this=0x7fffffffbd30, value=<error reading variable>, i=0, j=0) at /usr/include/eigen3/Eigen/src/Core/Visitor.h:133
133 res = value;
for more detals:
#0 0x000055555573fb54 in Eigen::internal::coeff_visitor<Eigen::Matrix<double, 1, -1, 1, 1, -1> >::init (this=0x7fffffffbd30, value=<error reading variable>, i=0,
j=0) at /usr/include/eigen3/Eigen/src/Core/Visitor.h:133
#1 0x0000555555739146 in Eigen::internal::visitor_impl<Eigen::internal::min_coeff_visitor<Eigen::Matrix<double, 1, -1, 1, 1, -1> >, Eigen::internal::visitor_evaluator<Eigen::Matrix<double, 1, -1, 1, 1, -1> >, -1>::run (mat=...,
visitor=...) at /usr/include/eigen3/Eigen/src/Core/Visitor.h:49
#2 0x0000555555731703 in Eigen::DenseBase<Eigen::Matrix<double, 1, -1, 1, 1, -1> >::visit<Eigen::internal::min_coeff_visitor<Eigen::Matrix<double, 1, -1, 1, 1, -1> > > (this=0x7fffffffbe10, visitor=...)
at /usr/include/eigen3/Eigen/src/Core/Visitor.h:116
#3 0x0000555555729e04 in Eigen::DenseBase<Eigen::Matrix<double, 1, -1, 1, 1, -1> >::minCoeff<unsigned long> (this=0x7fffffffbe10, index=0x7fffffffbe40)
at /usr/include/eigen3/Eigen/src/Core/Visitor.h:229
#4 0x0000555555721436 in PatchWork<PointXYZILID>::consensus_set_based_height_estimation (this=0x55555587e030, X=..., ranges=..., weights=...)
at /home/oem/Projects/water_surface_detect_ws/src/patchwork/include/patchwork/patchwork.hpp:416
#5 0x00005555557162c7 in PatchWork<PointXYZILID>::estimate_sensor_height (
this=0x55555587e030, cloud_in=...)
at /home/oem/Projects/water_surface_detect_ws/src/patchwork/include/patchwork/patchwork.hpp:478
--Type <RET> for more, q to quit, c to continue without paging--c
#6 0x000055555570b4c5 in PatchWork<PointXYZILID>::estimate_ground (this=0x55555587e030, cloud_in=..., cloud_out=..., cloud_nonground=..., time_taken=@0x5555558245e0: 0) at /home/oem/Projects/water_surface_detect_ws/src/patchwork/include/patchwork/patchwork.hpp:500
#7 0x00005555556ff793 in callbackNode (msg=...) at /home/oem/Projects/water_surface_detect_ws/src/patchwork/nodes/ros_kitti.cpp:90
#8 0x0000555555735c6e in boost::detail::function::void_function_invoker1<void (*)(boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&), void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&>::invoke (function_ptr=..., a0=...) at /usr/include/boost/function/function_template.hpp:117
#9 0x000055555574cade in boost::function1<void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&>::operator() (this=0x5555558f6490, a0=...) at /usr/include/boost/function/function_template.hpp:763
#10 0x0000555555744a00 in boost::detail::function::void_function_obj_invoker1<boost::function<void (boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&)>, void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> >::invoke(boost::detail::function::function_buffer&, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const>) (function_obj_ptr=..., a0=...) at /usr/include/boost/function/function_template.hpp:158
#11 0x00005555557af773 in boost::function1<void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> >::operator() (this=0x55555590b938, a0=...) at /usr/include/boost/function/function_template.hpp:763
#12 0x00005555557aef8d in ros::SubscriptionCallbackHelperT<boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&, void>::call (this=0x55555590b930, params=...) at /opt/ros/noetic/include/ros/subscription_callback_helper.h:144
#13 0x00007ffff7bc9139 in ros::SubscriptionQueue::call() () from /opt/ros/noetic/lib/libroscpp.so
#14 0x00007ffff7b77172 in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*) () from /opt/ros/noetic/lib/libroscpp.so
#15 0x00007ffff7b78883 in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/noetic/lib/libroscpp.so
#16 0x00007ffff7bcbfcf in ros::SingleThreadedSpinner::spin(ros::CallbackQueue*) () from /opt/ros/noetic/lib/libroscpp.so
#17 0x00007ffff7bb421f in ros::spin() () from /opt/ros/noetic/lib/libroscpp.so
#18 0x0000555555700eff in main (argc=1, argv=0x7fffffffd528) at /home/oem/Projects/water_surface_detect_ws/src/patchwork/nodes/ros_kitti.cpp:171
as for params.yaml, I just change the sensor height, the others did not change.
# 22.05.02 Update
# `sensor_height` denotes the elevation of the origin of the point cloud "with respect to the ground"
# So, it mostly have a positive value
# Note that if `patchwork/ATAT/ATAT_ON` is set to be true, the sensor_height is auto-calibrated
sensor_height: 2.5
# Extrinsics (Raw lidar coordinate -> Coordinate that is parallel to the X-Y plane of ground)
# But, not in use
extrinsic_trans: [0.0, 0.0, 0.0]
extrinsic_rot: [1, 0, 0,
0, 1, 0,
0, 0, 1]
patchwork:
mode: "czm"
verbose: true # To check effect of uprightness/elevation/flatness
visualize: true # Ground Likelihood Estimation is visualized
# Ground Plane Fitting parameters
num_iter: 3
num_lpr: 20
num_min_pts: 10
th_seeds: 0.5
th_dist: 0.125
max_r: 80.0
min_r: 2.7 # to consider vicinity of mobile plot form.
uprightness_thr: 0.707 # For uprightness. 45: 0.707 / 60: 0.866. The larger, the more conservative
# The points below the adaptive_seed_selection_margin * sensor_height are filtered
# For reject points caused by reflection or multipath problems.
# it should be lower than -1.0
adaptive_seed_selection_margin: -1.1
# It is not in the paper
# It is also not matched our philosophy, but it is employed to reject some FPs easily & intuitively.
# For patchwork, the global elevation threshold is only applied on Z3 and Z4
using_global_elevation: false
# W.r.t sensor frame (That is, if it is 0.0, then the candidates whose z is higher than z height of 3D LiDAR sensor are rejected
global_elevation_threshold: -0.5
# 22.05.02 Update
# ATAT is the abbrev. for All-Terrain Automatic heighT estimator
# It automatically corrects the wrong sensor height input
ATAT:
ATAT_ON: true
# 22.05.02 Update
# IMPORTANT - `max_r_for_ATAT` affects the quality of the estimation of sensor height
# If it is too large, then the z-elevation values of the bins become more ambiguous
# If it is too small, there is a potential risk that does not include the cloud points in the vicinity of the vehicles/mobile robots
# Therefore, it should be set appropriately!
max_r_for_ATAT: 5.0
num_sectors_for_ATAT: 20
noise_bound: 0.2
uniform: # deprecated
num_rings: 16
num_sectors: 54
czm:
# Note that `num_zones` == size of `num_sectors_each_zone` == size of `num_rings_each_zone` == size of `min_ranges` - 1
# To divide zones, max_r, min_r, and min_ranges are utilized
num_zones: 4
num_sectors_each_zone: [16, 32 ,54, 32]
num_rings_each_zone: [2, 4, 4, 4]
# Note that `min_r` == `min_ranges_each_zone`[0]!
min_ranges_each_zone: [2.7, 12.3625, 22.025, 41.35]
# 22.05.02 Update
# For usability, the MEANING OF THE ELEVATION THRESHOLDS IS CHANGED!!!!
# Original - the elevation w.r.t. to the sensor frame
# Modified - the elevation w.r.t. to the ground
# Thus, -sensor_height + elevation_threshold is the criteria.
# E.g. for the first ring, -1.723 (sensor height in the KITTI) + 0.523 = -1.2 becomes the criteria of the elevation filter
# That is, if the z-elevation of the bin is higher than -1.2, then the cloud points from the bin are rejected
elevation_thresholds: [0.523, 0.746, 0.879, 1.125] # For elevation. The size should be equal to flatness_thresholds vector
flatness_thresholds: [0.0005, 0.000725, 0.001, 0.001] # For flatness. The size should be equal to elevation_thresholds vector
I get your great work via LineFit. LineFit can not remove all water face point on my situation.
this is linefit extract water face points:
this is the useful points:
so, I want to use your work to check the performance on this situation
Sorry for late reply, but as a postdoc, I have lots of things to do for other researches, Haha, is it solved? If you want to keep continue, re-open this issue please!
Hi~ I want to use it on my SLAM, but after I change the topic in run_patchwork.launch, it warns
how could I just using your work to filter my point cloud?
Most Sincere Respect for You~~~