Giter Club home page Giter Club logo

linefit_ground_segmentation's Introduction

linefit_ground_segmentation

Implementation of the ground segmentation algorithm proposed in

@inproceedings{himmelsbach2010fast,
  title={Fast segmentation of 3d point clouds for ground vehicles},
  author={Himmelsbach, Michael and Hundelshausen, Felix V and Wuensche, H-J},
  booktitle={Intelligent Vehicles Symposium (IV), 2010 IEEE},
  pages={560--565},
  year={2010},
  organization={IEEE}
}

The linefit_ground_segmentation package contains the ground segmentation library. A ROS interface is available in linefit_ground_segmentation_ros

The library can be compiled separately from the ROS interface if you're not using ROS.

Installation

Requires the following dependencies to be installed:

  • catkin_simple https://github.com/catkin/catkin_simple.git
  • eigen_conversions sudo apt install ros-noetic-eigen-conversions

Compile using your favorite catkin build tool (e.g. catkin build linefit_ground_segmentation_ros)

Launch instructions

The ground segmentation ROS node can be launch by executing roslaunch linefit_ground_segmentation_ros segmentation.launch. Input and output topic names can be specified in the same file.

Getting up and running with your own point cloud source should be as simple as:

  1. Change the input_topic parameter in segmentation.launch to your topic.
  2. Adjust the sensor_height parameter in segmentation_params.yaml to the height where the sensor is mounted on your robot (e.g. KITTI Velodyne: 1.8m)

Parameter description

Parameters are set in linefit_ground_segmentation_ros/launch/segmentation_params.yaml

This algorithm works on the assumption that you known the height of the sensor above ground. Therefore, you have to adjust the sensor_height to your robot specifications, otherwise, it will not work.

The default parameters should work on the KITTI dataset.

Ground Condition

  • sensor_height Sensor height above ground.
  • max_dist_to_line maximum vertical distance of point to line to be considered ground.
  • max_slope Maximum slope of a line.
  • min_slope Minimum slope of a line.
  • max_fit_error Maximum error a point is allowed to have in a line fit.
  • max_start_height Maximum height difference between new point and estimated ground height to start a new line.
  • long_threshold Distance after which the max_height condition is applied.
  • max_height Maximum height difference between line points when they are farther apart than long_threshold.
  • line_search_angle How far to search in angular direction to find a line. A higher angle helps fill "holes" in the ground segmentation.
  • gravity_aligned_frame Name of a coordinate frame which has its z-axis aligned with gravity. If specified, the incoming point cloud will be rotated, but not translated into this coordinate frame. If left empty, the sensor frame will be used.

Segmentation

  • r_min Distance at which segmentation starts.
  • r_max Distance at which segmentation ends.
  • n_bins Number of radial bins.
  • n_segments Number of angular segments.

Other

  • n_threads Number of threads to use.
  • latch Latch output point clouds in ROS node.
  • visualize Visualize the segmentation result. ONLY FOR DEBUGGING. Do not set true during online operation.

linefit_ground_segmentation's People

Contributors

lorenwel avatar yoshuanava avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

linefit_ground_segmentation's Issues

should there be a ()

linefit_ground_segmentation/src/segment.cc line47

Wondering if it should be a bracket wrapping around the last two bools such as following
if (error > max_error_ || std::fabs(cur_line.first) > max_slope_ || (is_long_line && std::fabs(expected_z - cur_point.z) > max_long_height_) )

Ouster cloud segmentation

Hi @lorenwel ,
Thanks for the amazing work.
I have been using your ros package with ouster LiDAR and there is a typical performance of 100ms.
For reducing this time, I used threads in addition to the ones you used.
Is there any other way to improve performance of the implementation ?
Regards,
Bruno

Error launching line_fit_ros

Hi,
I launched line_fit_ros in a separate workspace in ROS and I obtained the following error:


[segmentation.launch] is neither a launch file in package [linefit_ground_segmentation_ros] nor is [linefit_ground_segmentation_ros] a launch file name
The traceback for the exception was written to the log file

What could be the issue?
Regards,
Bruno

ground_segmentation_test-2 died for using GPU

hi, i have some trouble while using this, it is ok when i using Linux 5.16 without gpu to run the test.launch.
but, when i use Linux 5.10.10-051010-generic with gpu, i got [ground_segmentation_test-2] process has died.
i test the code, found out that the process die at GroundSegmentation::resetSegments(), is that ok for you to give me some help?
thank you very much!

Issue whan launching segmentation.node

Hello and thanks for the great work!
I wanted to test the repo but I cannot somehow launch the node because I get this error:

roslaunch linefit_ground_segmentation_ros segmentation.launch

Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://localhost:42143/

SUMMARY
========

PARAMETERS
 * /ground_segmentation/gravity_aligned_frame: 
 * /ground_segmentation/ground_output_topic: ground_cloud
 * /ground_segmentation/input_topic: /kitti/velo/point...
 * /ground_segmentation/latch: False
 * /ground_segmentation/line_search_angle: 0.1
 * /ground_segmentation/long_threshold: 1.0
 * /ground_segmentation/max_dist_to_line: 0.05
 * /ground_segmentation/max_fit_error: 0.05
 * /ground_segmentation/max_long_height: 0.1
 * /ground_segmentation/max_slope: 0.3
 * /ground_segmentation/max_start_height: 0.2
 * /ground_segmentation/min_slope: 0.0
 * /ground_segmentation/n_bins: 120
 * /ground_segmentation/n_segments: 360
 * /ground_segmentation/n_threads: 4
 * /ground_segmentation/obstacle_output_topic: obstacle_cloud
 * /ground_segmentation/r_max: 50
 * /ground_segmentation/r_min: 0.5
 * /ground_segmentation/sensor_height: 1.8
 * /ground_segmentation/visualize: False
 * /rosdistro: noetic
 * /rosversion: 1.15.14

NODES
  /
    ground_segmentation (linefit_ground_segmentation_ros/ground_segmentation_node)

auto-starting new master
process[master]: started with pid [17201]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 70bd43ea-1cac-11ed-8083-04d9f5f773c7
process[rosout-1]: started with pid [17226]
started core service [/rosout]
process[ground_segmentation-2]: started with pid [17233]
/home/catkin_ws/devel/lib/linefit_ground_segmentation_ros/ground_segmentation_node: symbol lookup error: /home/catkin_ws/devel/lib/liblinefit_ground_segmentation.so: undefined symbol: _ZNK3pcl13visualization28PointCloudGeometryHandlerXYZINS_8PointXYZEE11getGeometryER15vtkSmartPointerI9vtkPointsE
[ground_segmentation-2] process has died 

Not sure if it has anything to do with the repo, this were my commands:

sudo apt install ros-noetic-eigen-conversions
mkdir -p catkin_ws/src
cd catkin_ws && catkin init
cd src
git clone https://github.com/catkin/catkin_simple.git
git clone https://github.com/lorenwel/linefit_ground_segmentation.git
cd ..
catkin build 
source devel/setup.bash
roslaunch linefit_ground_segmentation_ros segmentation.launch

ground_segmentation_test_node.cc:9: undefined reference to `google::InitGoogleLogging(char const*)'?

When i build caode using catkin_make got the error below. KIndly help

In function main': /home/administrator/catkin_ws1/src/linefit_ground_segmentation_ros/src/ground_segmentation_test_node.cc:9: undefined reference to google::InitGoogleLogging(char const*)'
/home/administrator/catkin_ws1/src/linefit_ground_segmentation_ros/src/ground_segmentation_test_node.cc:43: undefined reference to GroundSegmentation::GroundSegmentation(GroundSegmentationParams const&)' /home/administrator/catkin_ws1/src/linefit_ground_segmentation_ros/src/ground_segmentation_test_node.cc:46: undefined reference to GroundSegmentation::segment(pcl::PointCloudpcl::PointXYZ const&, std::vector<int, std::allocator >)'
collect2: error: ld returned 1 exit status
linefit_ground_segmentation_ros/CMakeFiles/ground_segmentation_test_node.dir/build.make:708: recipe for target '/home/administrator/catkin_ws1/devel/lib/linefit_ground_segmentation_ros/ground_segmentation_test_node' failed
make[2]: *** [/home/administrator/catkin_ws1/devel/lib/linefit_ground_segmentation_ros/ground_segmentation_test_node] Error 1
CMakeFiles/Makefile2:377: recipe for target 'linefit_ground_segmentation_ros/CMakeFiles/ground_segmentation_test_node.dir/all' failed
make[1]: *** [linefit_ground_segmentation_ros/CMakeFiles/ground_segmentation_test_node.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
CMakeFiles/ground_segmentation_node.dir/src/ground_segmentation_node.cc.o: In function main': /home/administrator/catkin_ws1/src/linefit_ground_segmentation_ros/src/ground_segmentation_node.cc:41: undefined reference to google::InitGoogleLogging(char const
)'
CMakeFiles/ground_segmentation_node.dir/src/ground_segmentation_node.cc.o: In function SegmentationNode::scanCallback(pcl::PointCloud<pcl::PointXYZ> const&)': /home/administrator/catkin_ws1/src/linefit_ground_segmentation_ros/src/ground_segmentation_node.cc:23: undefined reference to GroundSegmentation::GroundSegmentation(GroundSegmentationParams const&)'
/home/administrator/catkin_ws1/src/linefit_ground_segmentation_ros/src/ground_segmentation_node.cc:26: undefined reference to `GroundSegmentation::segment(pcl::PointCloudpcl::PointXYZ const&, std::vector<int, std::allocator >*)'
collect2: error: ld returned 1 exit status
linefit_ground_segmentation_ros/CMakeFiles/ground_segmentation_node.dir/build.make:708: recipe for target '/home/administrator/catkin_ws1/devel/lib/linefit_ground_segmentation_ros/ground_segmentation_node' failed
make[2]: *** [/home/administrator/catkin_ws1/devel/lib/linefit_ground_segmentation_ros/ground_segmentation_node] Error 1
CMakeFiles/Makefile2:414: recipe for target 'linefit_ground_segmentation_ros/CMakeFiles/ground_segmentation_node.dir/all' failed
make[1]: *** [linefit_ground_segmentation_ros/CMakeFiles/ground_segmentation_node.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2

Why is the maximum distance taken here, not the smaller one?

    const double dist_1 = segments_[index_1].verticalDistanceToLine(point_2d.d, point_2d.z);
    const double dist_2 = segments_[index_2].verticalDistanceToLine(point_2d.d, point_2d.z);
    // Select larger distance if both segments return a valid distance.
    if (dist_1 > dist) {
      dist = dist_1;
    }
    if (dist_2 > dist) {
      dist = dist_2;
    }

Compatability with rslidar 16

Dear Author, thanks for sharing your work!
I tried to segment the ground of scanned clouds generated by rslidar16. It is a lot sparser compared to KITTI data. The result is very poor. The white-colored cloud is what is left after segmentation.
rviz_screenshot_2021_09_22-19_34_50

origin data

I want the original packet .bag when you tested.

Simulation has strange artifacts on flat ground

In simulation, the algorithm finds strange obstacle points on flat ground. In the image, the red points are lidar points found as obstacles:
Screenshot from 2020-01-16 12-27-23

A bag with the original points clouds (in the "velodyne" tf frame)
2020-01-16-12-22-28.zip

The params

n_threads: 4            # number of threads to use.

r_min: 0.5              # minimum point distance.
r_max: 50               # maximum point distance.
n_bins: 120             # number of radial bins.
n_segments: 12         # number of radial segments.

max_dist_to_line: 0.05  # maximum vertical distance of point to line to be considered ground.

sensor_height: .425      # sensor height above ground.
max_slope: 0.15          # maximum slope of a ground line.
max_fit_error: 0.05     # maximum error of a point during line fit.
long_threshold: 2.0     # distance between points after which they are considered far from each other.
max_long_height: 0.1    # maximum height change to previous point in long line.
max_start_height: 0.2   # maximum difference to estimated ground height to start a new line.
line_search_angle: 0.1  # how far to search in angular direction to find a line [rad].

latch: false            # latch output topics or not
visualize: false        # visualize segmentation result - USE ONLY FOR DEBUGGING

catkin_make fails

Hello,

during catkin_make i receive the following warnings:

__-- Could NOT find ensenso (missing: ENSENSO_LIBRARY ENSENSO_INCLUDE_DIR)
** WARNING ** io features related to ensenso will be disabled
-- Could NOT find DAVIDSDK (missing: DAVIDSDK_LIBRARY DAVIDSDK_INCLUDE_DIR)
** WARNING ** io features related to davidSDK will be disabled
-- Could NOT find DSSDK (missing: _DSSDK_LIBRARIES)
** WARNING ** io features related to dssdk will be disabled
** WARNING ** io features related to pcap will be disabled
** WARNING ** io features related to png will be disabled
-- The imported target "vtk" references the file
"/usr/bin/vtk"
but this file does not exist. Possible reasons include:

The file was deleted, renamed, or moved to another location.
An install or uninstall procedure did not complete successfully.
The installation package was faulty and contained
"/usr/lib/cmake/vtk-6.2/VTKTargets.cmake"
but not all the files it references.__

I could solve the ensenso and DAVIDSDK, with installing ENSENSO und DAVIDSDK. Finally catkin_make fail with:
CMake Error at as_ros/src/linefit_ground_segmentation/linefit_ground_segmentation_ros/CMakeLists.txt:29 (add_custom_target):
add_custom_target cannot create target "headers" because another target
with the same name already exists. The existing target is a custom target
created in source directory
"/home/robert/catkin_ws/src/as_ros/src/linefit_ground_segmentation/linefit_ground_segmentation".
See documentation for policy CMP0002 for more details.

I would really appreciate your help. I am using ROS Melodic and Ubuntu 18.04. All Prerequirements should be completed.

Kindly regards

Error launching line_fit_ros

I launched line_fit_ros in a separate workspace in ROS and I obtained the following error:

[segmentation.launch] is neither a launch file in package [linefit_ground_segmentation_ros] nor is [linefit_ground_segmentation_ros] a launch file name
The traceback for the exception was written to the log file
@lorenwel kindly help

Bin/segment indices out of bound

Hi,
First of all, thank you for sharing your algorithm! I'm currently using it for interfacing ethz-asl/SegMap with a custom LiDAR SLAM pipeline that I developed for my thesis. It has worked great.

When I first tried to use your pkg for segmenting out Velodyne pointclouds, as those from KITTI, I got some issues with the bin and segment indices going out of bound:

segments_[segment_index][bin_index].addPoint(range, point.z);

I have submitted a pull request with a patch for this. #4

Kind regards,
Yoshua Nava

somthing wrong when using [Viewer] in test file

hey, thanks for your great work. but there're sth wrong when using it, and i still have some problems after debugging.

1.run the test_node.launch, crash before seg(almost after the visual window flash),
and get the bug as follows(debug output using GBD)
p.s.nothing changed in this work.
image
so it seems that sth wrong about vtk/visualize

2.close the visualize func, and it runs well(can get point segmentation)
so the problem seems in viewer class .
cause it crash before seg and visual func in segmentation file, the problem may be in this part?(please correct me if wrong)
image
i don't really konw what this part means, especially why 2 for-loop??
could you please explain this part?

3.my pcl is 1.8 and vtk is 6.3, what's the recommand version?
is this problem caused by pkg version?

hope you can give me some advice. thanks a lot!

Pkg identifiers in launch files do not match real package names

The package identifiers from the launchfiles:

<node name="ground_segmentation" pkg="ground_segmentation" type="ground_segmentation_node">

<node name="ground_segmentation_test" pkg="ground_segmentation" type="ground_segmentation_test_node" output="screen">

Do not correspond with the real name of this package ROS wrapper:

<name>linefit_ground_segmentation_ros</name>

I have submitted a pull request to fix this, #9

Eigen/gtsam error when solving linear system

Hi,
When I try to use a GroundSegmentation object, along with a SegMatchWorker from SegMap for my algorithm, I get an error with the following backtrace:

0x00007ffff767643a in Eigen::internal::gebp_kernel<double, double, long, 4, 4, false, false>::operator()(double*, long, double const*, double const*, long, long, long, double, long, long, long, long, double*) [clone .constprop.1215] ()
   from /home/alfredoso/Robotics/Dependencies/asl_depends_ws/devel/lib/libgtsam.so.4
(gdb) bt
#0  0x00007ffff767643a in Eigen::internal::gebp_kernel<double, double, long, 4, 4, false, false>::operator()(double*, long, double const*, double const*, long, long, long, double, long, long, long, long, double*) [clone .constprop.1215] ()
   from /home/alfredoso/Robotics/Dependencies/asl_depends_ws/devel/lib/libgtsam.so.4
#1  0x00007ffff7695c55 in Eigen::internal::general_matrix_matrix_product<long, double, 0, false, double, 0, false, 0>::run(long, long, long, double const*, long, double const*, long, double*, long, double, Eigen::internal::level3_blocking<double, double>&, Eigen::internal::GemmParallelInfo<long>*) () from /home/alfredoso/Robotics/Dependencies/asl_depends_ws/devel/lib/libgtsam.so.4
#2  0x00007ffff4342ec2 in Eigen::internal::gemm_functor<double, long, Eigen::internal::general_matrix_matrix_product<long, double, 0, false, double, 0, false, 0>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::internal::gemm_blocking_space<0, double, double, -1, -1, -1, 1, false> >::operator() (info=0x0, cols=<optimized out>, col=0, rows=<optimized out>, row=0, this=<optimized out>)
    at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h:229
#3  Eigen::internal::parallelize_gemm<true, Eigen::internal::gemm_functor<double, long, Eigen::internal::general_matrix_matrix_product<long, double, 0, false, double, 0, false, 0>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::internal::gemm_blocking_space<0, double, double, -1, -1, -1, 1, false> >, long> (transpose=false, cols=<optimized out>, rows=<optimized out>, func=...) at /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h:96
#4  Eigen::internal::generic_product_impl<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::DenseShape, Eigen::DenseShape, 8>::scaleAndAddTo<Eigen::Matrix<double, -1, -1, 0, -1, -1> > (alpha=<optimized out>, a_rhs=..., 
    a_lhs=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h:487
#5  Eigen::internal::generic_product_impl<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::DenseShape, Eigen::DenseShape, 8>::evalTo<Eigen::Matrix<double, -1, -1, 0, -1, -1> > (rhs=..., lhs=..., dst=...)
    at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h:439
#6  Eigen::internal::Assignment<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::internal::assign_op<double>, Eigen::internal::Dense2Dense, double>::run (src=..., 
    dst=...) at /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h:133
#7  Eigen::internal::call_assignment_no_alias<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::internal::assign_op<double> > (func=..., src=..., dst=...)
    at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:747
#8  Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::_set_noalias<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > (other=..., this=0x7fff8f7f62c0)
    at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:700
#9  Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::_init1<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > (other=..., this=0x7fff8f7f62c0) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:783
#10 Eigen::Matrix<double, -1, -1, 0, -1, -1>::Matrix<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > (x=..., this=0x7fff8f7f62c0) at /usr/include/eigen3/Eigen/src/Core/Matrix.h:296
#11 Eigen::internal::Assignment<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::internal::assign_op<double>, Eigen::internal::Dense2Dense, double>::run (src=..., dst=...) at /usr/include/eigen3/Eigen/src/LU/InverseImpl.h:304
#12 Eigen::internal::call_assignment_no_alias<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::internal::assign_op<double> > (dst=..., src=..., 
    func=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:747
#13 0x00007ffff4343d3e in Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::_set_noalias<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > > (other=..., this=0x7fff8f7f6520)
    at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:700
#14 Eigen::PlainObjectBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::PlainObjectBase<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > > (other=..., this=0x7fff8f7f6520)
    at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:510
#15 Eigen::Matrix<double, -1, -1, 0, -1, -1>::Matrix<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> > > (other=..., this=0x7fff8f7f6520) at /usr/include/eigen3/Eigen/src/Core/Matrix.h:379
#16 Eigen::internal::generic_product_impl<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::DenseShape, Eigen::DenseShape, 8>::scaleAndAddTo<Eigen::Matrix<double, -1, -1, 0, -1, -1> > (alpha=<optimized out>, a_rhs=..., a_lhs=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h:468
#17 Eigen::internal::generic_product_impl<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::DenseShape, Eigen::DenseShape, 8>::evalTo<Eigen::Matrix<double, -1, -1, 0, -1, -1> > (rhs=..., lhs=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h:439
#18 Eigen::internal::product_evaluator<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, 8, Eigen::DenseShape, Eigen::DenseShape, double, double>::product_evaluator (xpr=..., this=0x7fff8f7f65d0) at /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h:117
#19 Eigen::internal::evaluator<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >::evaluator (xpr=..., this=0x7fff8f7f65d0)
    at /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h:35
#20 Eigen::internal::evaluator<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const>::evaluator (xpr=..., this=0x7fff8f7f65d0)
    at /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h:94
#21 Eigen::internal::unary_evaluator<Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true>, Eigen::internal::IndexBased, double>::unary_evaluator (block=..., this=0x7fff8f7f65c8) at /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h:760
#22 Eigen::internal::block_evaluator<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true, false>::block_evaluator (
    block=..., this=0x7fff8f7f65c8) at /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h:747
#23 Eigen::internal::evaluator<Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> >::evaluator (block=..., 
    this=0x7fff8f7f65c8) at /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h:733
#24 Eigen::internal::evaluator<Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const>::evaluator (
    xpr=..., this=0x7fff8f7f65c8) at /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h:94
#25 Eigen::internal::unary_evaluator<Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const>, Eigen::internal::IndexBased, double>::unary_evaluator (op=..., this=0x7fff8f7f65c0) at /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h:385
#26 Eigen::internal::evaluator<Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const> >::evaluator (xpr=..., this=0x7fff8f7f65c0) at /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h:84
#27 Eigen::internal::call_dense_assignment_loop<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const>, Eigen::internal::add_assign_op<double> > (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:648
#28 Eigen::internal::Assignment<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const>, Eigen::internal::add_assign_op<double>, Eigen::internal::Dense2Dense, double>::run (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:790
#29 Eigen::internal::call_assignment_no_alias<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const>, Eigen::internal::add_assign_op<double> > (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:747
#30 Eigen::internal::call_assignment<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const>, Eigen::internal::add_assign_op<double> >(Eigen::Matrix<double, -1, 1, 0, -1, 1>&, Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const> const&, Eigen::internal::add_assign_op<double> const&, Eigen::internal::enable_if<!Eigen::internal::evaluator_assume_aliasing<Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const>, Eigen::internal::evaluator_traits<Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const> >::Shape>::value, void*>::type) (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:712
#31 Eigen::MatrixBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::operator+=<Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<double>, Eigen::Block<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> const, -1, 1, true> const> > (other=..., this=0x7fff8f7f66c0) at /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h:177
#32 Eigen::internal::gemv_dense_selector<2, 0, false>::run<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::Matrix<double, -1, 1, 0, -1, 1> > (alpha=<optimized out>, dest=..., rhs=..., lhs=...) at /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h:357
#33 Eigen::internal::generic_product_impl<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::D---Type <return> to continue, or q <return> to quit---
enseShape, Eigen::DenseShape, 7>::scaleAndAddTo<Eigen::Matrix<double, -1, 1, 0, -1, 1> > (alpha=<optimized out>, rhs=..., lhs=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h:349
#34 Eigen::internal::generic_product_impl_base<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::internal::generic_product_impl<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::DenseShape, Eigen::DenseShape, 7> >::scaleAndAddTo<Eigen::Matrix<double, -1, 1, 0, -1, 1> > (alpha=<optimized out>, rhs=..., lhs=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h:334
#35 Eigen::internal::generic_product_impl_base<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::internal::generic_product_impl<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::DenseShape, Eigen::DenseShape, 7> >::evalTo<Eigen::Matrix<double, -1, 1, 0, -1, 1> > (dst=..., lhs=..., rhs=...) at /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h:322
#36 0x00007ffff433d3e1 in Eigen::internal::Assignment<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::Product<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0>, Eigen::internal::assign_op<double>, Eigen::internal::Dense2Dense, double>::run (src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h:133
#37 Eigen::internal::call_assignment_no_alias<Eigen::Matrix<double, -1, 1, 0, -1, 1>, Eigen::Product<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0>, Eigen::internal::assign_op<double> > (func=..., src=..., dst=...) at /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h:747
#38 Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::_set_noalias<Eigen::Product<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0> > (other=..., this=<optimized out>) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:700
#39 Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::PlainObjectBase<Eigen::Product<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0> > (other=..., this=0x7fff8f7f66c0) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:510
#40 Eigen::Matrix<double, -1, 1, 0, -1, 1>::Matrix<Eigen::Product<Eigen::Product<Eigen::Inverse<Eigen::Product<Eigen::Matrix<double, -1, -1, 0, -1, -1>, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0> >, Eigen::Matrix<double, -1, -1, 0, -1, -1>, 0>, Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0> > (other=..., this=0x7fff8f7f66c0) at /usr/include/eigen3/Eigen/src/Core/Matrix.h:379
#41 Segment::fitLocalLine (this=this@entry=0x7fffa819ecc0, points=...) at /home/alfredoso/Robotics/SCRThesis/Thesis_ws/src/linefit_ground_segmentation/linefit_ground_segmentation/src/segment.cc:145

#42 0x00007ffff433d6d7 in Segment::fitSegmentLines (this=0x7fffa819ecc0) at /home/alfredoso/Robotics/SCRThesis/Thesis_ws/src/linefit_ground_segmentation/linefit_ground_segmentation/src/segment.cc:42
#43 0x00007ffff4331ef8 in GroundSegmentation::lineFitThread (this=0x7fffbeff4060, start_index=<optimized out>, end_index=180, lines=0x0, lines_mutex=0x7fffbeff3e10)
    at /home/alfredoso/Robotics/SCRThesis/Thesis_ws/src/linefit_ground_segmentation/linefit_ground_segmentation/src/ground_segmentation.cc:118
#44 0x00007ffff4e0dc80 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#45 0x00007ffff60036fa in start_thread (arg=0x7fff8f7fe700) at pthread_create.c:333
#46 0x00007ffff487cb5d in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:109

By doing some experiments, I found out that it is related to the way in which we solve the linear system for line fitting:

const Eigen::VectorXd result = (X_t * X).inverse() * X_t * Y;

I submitted a pull request to fix this, #6

Running a little bit slow

Hi, I just run this code with kitti dataset, but the terminal shows the algorithm cost more than 100ms for one frame.

"segmentation.launch" file has a mistake

Hi!
Thanks for your open-source code!
But there is a little wrong with the launch file.

segmentation.launch line 6
<param name="input_topic" value="/dynamic_point_cloud" />
should be in the node of ground_segmentation tag.

Points obvious in the ground plane were treated as obstacle points, why?

Hi, I am using this segmentation package for point clouds capturing by the stereo camera and found that there are some speckles in the ground were treated as obstacle points. Those speckles were typically located on the edge of camera's FOV (please check the picture, in this scene, there is a little slope and some small items on it, orange points are obstacle_cloud), and my yaml look like this:

n_threads: 4            # number of threads to use.

r_min: 0.05              # minimum point distance. 0.5
r_max: 6              # maximum point distance. 50
n_bins: 120             # number of radial bins. 120
n_segments: 90         # number of radial segments. 360

max_dist_to_line: 0.03  # maximum vertical distance of point to line to be considered ground. 0.05

sensor_height: 0.075      # sensor height above ground. 1.8
max_slope: 0.3          # maximum slope of a ground line. 0.3
max_fit_error: 0.05     # maximum error of a point during line fit. 0.05
long_threshold: 0.1    # distance between points after which they are considered far from each other. 1.0
max_long_height: 0.1    # maximum height change to previous point in long line. 0.1
max_start_height: 0.2  # maximum difference to estimated ground height to start a new line. 0.2
line_search_angle: 0.1  # how far to search in angular direction to find a line [rad]. 0.1

latch: false            # latch output topics or not
visualize: false        # visualize segmentation result - USE ONLY FOR DEBUGGING

I will be really appreciated if anyone can help me solve this issue. Thanks!
text4806

segment.cc > no good line condition

This condition below covers not good line condition.
https://github.com/lorenwel/linefit_ground_segmentation/blob/master/linefit_ground_segmentation/src/segment.cc#L47

Wondering why following two segments need t be included in this condition (segment.cc > ln50-ln59) ?
// Don't let lines with 2 base points through. if (current_line_points.size() >= 3) { const LocalLine new_line = fitLocalLine(current_line_points); lines_.push_back(localLineToLine(new_line, current_line_points)); cur_ground_height = new_line.first * current_line_points.back().d + new_line.second; }

// Start new line. is_long_line = false; current_line_points.erase(current_line_points.begin(), --current_line_points.end()); --line_iter;

I thought the above two segments should be executed for good line. Correct me if wrong. Thank you very much in advance!

how to visualize the results

Hi,@lorenwel , Thanks for your open-source code!But I don not know how to visualize the results. I modified the file path in the test.launch and run roslaunch linefit_ground_segmentation_ros tset.launch, but I can't see any results, what's wrong?

Output stuck on first frame

Thanks for your excellent work.
I was trying to implement this code however the output is always stuck on the first frame (when using the visualizer) and there is no points on the output topic when viewed in RViz. This happens with both the provided file and with my own dataset.
The points appear to be segmented but it is only the first frame that is visible.
The output on screen simply says

Segmenting cloud with 122527 points...

I used catkin build configured to 'Release' type. The 3D Viewer indicates around 70 FPS however the output is frozen

Which version of pcl is recommended?

Hello.
Thank you for your great project.

I got the following error when I catkin build in my environment (WSL2, Ubuntu20.04, ROS noetic).
The file structure is as follows.

catkin_ws
└── src
    ├── linefit_ground_segmentation
    │   ├── CMakeLists.txt
    │   ├── include
    │   │   └── ground_segmentation
    │   │       ├── bin.h
    │   │       ├── ground_segmentation.h
    │   │       ├── segment.h
    │   │       ├── typedefs.h
    │   │       └── viewer.h
    │   ├── package.xml
    │   └── src
    │       ├── bin.cc
    │       ├── ground_segmentation.cc
    │       ├── segment.cc
    │       └── viewer.cc
    ├── linefit_ground_segmentation_ros
    │   ├── CMakeLists.txt
    │   ├── launch
    │   │   ├── segmentation.launch
    │   │   ├── segmentation_params.yaml
    │   │   └── test.launch
    │   ├── package.xml
    │   └── src
    │       ├── ground_segmentation_node.cc
    │       └── ground_segmentation_test_node.cc
_________________________________________________________________________________________________________________________________________
Errors     << linefit_ground_segmentation:make /home/yuki/catkin_ws/logs/linefit_ground_segmentation/build.make.000.log
/home/yuki/catkin_ws/src/linefit_ground_segmentation/src/ground_segmentation.cc: In member function ‘void GroundSegmentation::segment(const PointCloud&, std::vector<int>*)’:
/home/yuki/catkin_ws/src/linefit_ground_segmentation/src/ground_segmentation.cc:51:66: error: conversion from ‘std::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >’ to non-scalar type ‘pcl::PointCloud<pcl::PointXYZ>::Ptr’ {aka ‘boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >’} requested
   51 |     PointCloud::Ptr obstacle_cloud = std::make_shared<PointCloud>();
      |                                      ~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~
/home/yuki/catkin_ws/src/linefit_ground_segmentation/src/ground_segmentation.cc:54:64: error: conversion from ‘std::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >’ to non-scalar type ‘pcl::PointCloud<pcl::PointXYZ>::Ptr’ {aka ‘boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >’} requested
   54 |     PointCloud::Ptr ground_cloud = std::make_shared<PointCloud>();
      |                                    ~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~
/home/yuki/catkin_ws/src/linefit_ground_segmentation/src/ground_segmentation.cc:60:61: error: conversion from ‘std::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >’ to non-scalar type ‘pcl::PointCloud<pcl::PointXYZ>::Ptr’ {aka ‘boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >’} requested
   60 |     PointCloud::Ptr min_cloud = std::make_shared<PointCloud>();
      |                                 ~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~
make[2]: *** [CMakeFiles/linefit_ground_segmentation.dir/build.make:63: CMakeFiles/linefit_ground_segmentation.dir/src/ground_segmentation.cc.o] エラー 1
make[2]: *** 未完了のジョブを待っています....
make[1]: *** [CMakeFiles/Makefile2:305: CMakeFiles/linefit_ground_segmentation.dir/all] エラー 2
make: *** [Makefile:141: all] エラー 2
cd /home/yuki/catkin_ws/build/linefit_ground_segmentation; catkin build --get-env linefit_ground_segmentation | catkin env -si  /usr/bin/make --jobserver-auth=3,4; cd -

.........................................................................................................................................
Failed     << linefit_ground_segmentation:make               [ Exited with code 2 ]
Failed    <<< linefit_ground_segmentation                    [ 14.4 seconds ]
Abandoned <<< linefit_ground_segmentation_ros                [ Unrelated job failed ]

This is probably a problem because the desired pcl version is not installed.
And the pcl version in my environment is described as Version: 1.10.0+dfsg-5ubuntu1 when checked with apt show libpcl-dev.

Which version is the author using?
If it is not a version difference, what is the problem?

Thank you in advance.

How to adopt the algorithm to point cloud from 16-beams VLP16?

Thank you for your excellent work! I am wondering how can I adjust the parameters, or even the algorithm, to make it perform well on point cloud collected by 16 beams LiDAR like VLP-16? I found you mentioned changing sensor_height in another issue, is there any additional adjustment to be done, as I found that param change didn't improve the performance?

Segmentation Fault

I tried to run the node, but it seems to crash. It processes like 5-8 clouds and then crashes. When using gdb, it throws and segmentation fault. Do you know a solution?

building

hi, can you please walk me through the steps on how to build this?
i'm trying to use this without ROS.
do i put catkin_simple into linefit_ground_segmentation/linefit_ground_segmentation?
what do i do next?

HI!

Hello and thanks for the great work!
May I ask whether the two-point connection is a long straight line in the process of straight line fitting?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.