Error while building this package
YoushaaMurhij opened this issue · 7 comments
YoushaaMurhij commented
-- Configuring done
-- Generating done
-- Build files have been written to: /home/---/LidarPerception_ws/build
####
#### Running command: "make -j6 -l6" in "/home/---/LidarPerception_ws/build"
####
[ 0%] Built target std_msgs_generate_messages_cpp
[ 0%] Built target sensor_msgs_generate_messages_cpp
[ 0%] Built target std_msgs_generate_messages_py
[ 0%] Built target sensor_msgs_generate_messages_py
[ 0%] Built target _autosense_msgs_generate_messages_check_deps_TrackingObjectArray
[ 0%] Built target _autosense_msgs_generate_messages_check_deps_TrackingFixedTrajectoryArray
[ 0%] Built target _autosense_msgs_generate_messages_check_deps_PointCloud2Array
Geneate messages link into common include
[ 10%] Built target autosense_msgs_generate_messages_py
[ 18%] Built target autosense_msgs_generate_messages_cpp
[ 18%] Built target autosense_msgs_generate_messages
[ 24%] Built target common_lib
[ 29%] Built target roi_filters_lib
[ 40%] Built target feature_extractors_lib
[ 45%] Built target object_builders_lib
[ 48%] Building CXX object perception/libs/segmenters/CMakeFiles/segmenters_lib.dir/src/don_segmenter.cpp.o
[ 67%] Built target tracking_lib
In file included from /usr/include/c++/9/vector:67,
from /usr/include/eigen3/Eigen/StdVector:15,
from /usr/include/pcl-1.10/pcl/pcl_base.h:49,
from /usr/include/pcl-1.10/pcl/features/feature.h:48,
from /usr/include/pcl-1.10/pcl/features/don.h:41,
from /home/---/LidarPerception_ws/src/perception/libs/segmenters/include/segmenters/don_segmenter.hpp:8,
from /home/---/LidarPerception_ws/src/perception/libs/segmenters/src/don_segmenter.cpp:5:
/usr/include/c++/9/bits/stl_vector.h: In instantiation of ‘struct std::_Vector_base<int, pcl::PointXYZI>’:
/usr/include/c++/9/bits/stl_vector.h:386:11: required from ‘class std::vector<int, pcl::PointXYZI>’
/home/---/LidarPerception_ws/src/perception/libs/segmenters/src/don_segmenter.cpp:108:53: required from here
/usr/include/c++/9/bits/stl_vector.h:84:21: error: no type named ‘value_type’ in ‘struct pcl::PointXYZI’
84 | rebind<_Tp>::other _Tp_alloc_type;
| ^~~~~~~~~~~~~~
/usr/include/c++/9/bits/stl_vector.h:86:9: error: no type named ‘value_type’ in ‘struct pcl::PointXYZI’
86 | pointer;
| ^~~~~~~
/usr/include/c++/9/bits/stl_vector.h: In instantiation of ‘class std::vector<int, pcl::PointXYZI>’:
/home/---/LidarPerception_ws/src/perception/libs/segmenters/src/don_segmenter.cpp:108:53: required from here
/usr/include/c++/9/bits/stl_vector.h:387:5: error: no type named ‘value_type’ in ‘struct pcl::PointXYZI’
387 | {
| ^
/usr/include/c++/9/bits/stl_vector.h:471:20: error: no members matching ‘std::vector<int, pcl::PointXYZI>::_Base {aka std::_Vector_base<int, pcl::PointXYZI>}::_M_allocate’ in ‘std::vector<int, pcl::PointXYZI>::_Base’ {aka ‘struct std::_Vector_base<int, pcl::PointXYZI>’}
471 | using _Base::_M_allocate;
| ^~~~~~~~~~~
/usr/include/c++/9/bits/stl_vector.h:472:20: error: no members matching ‘std::vector<int, pcl::PointXYZI>::_Base {aka std::_Vector_base<int, pcl::PointXYZI>}::_M_deallocate’ in ‘std::vector<int, pcl::PointXYZI>::_Base’ {aka ‘struct std::_Vector_base<int, pcl::PointXYZI>’}
472 | using _Base::_M_deallocate;
| ^~~~~~~~~~~~~
/usr/include/c++/9/bits/stl_vector.h:474:20: error: no members matching ‘std::vector<int, pcl::PointXYZI>::_Base {aka std::_Vector_base<int, pcl::PointXYZI>}::_M_get_Tp_allocator’ in ‘std::vector<int, pcl::PointXYZI>::_Base’ {aka ‘struct std::_Vector_base<int, pcl::PointXYZI>’}
474 | using _Base::_M_get_Tp_allocator;
| ^~~~~~~~~~~~~~~~~~~
make[2]: *** [perception/libs/segmenters/CMakeFiles/segmenters_lib.dir/build.make:128: perception/libs/segmenters/CMakeFiles/segmenters_lib.dir/src/don_segmenter.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:3116: perception/libs/segmenters/CMakeFiles/segmenters_lib.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
Invoking "make -j6 -l6" failed
Durant35 commented
@YoushaaMurhij Seems you fixed it? without any comment?
YoushaaMurhij commented
No, I could not fixed it! I thought no one faced this error before.
I think it is related to the used version of ROS and Python
Durant35 commented
Found your PCL version: 1.10, currently I have verified PCL 1.7, PCL 1.9 only, maybe you can have a try.
Durant35 commented
Never mind to keep it open until fixed.
atasoglou commented
I am also getting this error using pcl 1.10. What I did is, I just did a bit of code unrolling for pcl::copyPointCloud<PointN, PointI>()
because the problem is with that call.
So the for-loop:
for (; iter != clusters_indices.end(); ++iter) {}
Becomes:
for (const pcl::PointIndices & indices : clusters_indices) {
PointICloudPtr cluster(new PointICloud);
pcl::PointCloud<pcl::PointNormal> cloud_in = *don_cloud_filtered;
pcl::PointCloud<pcl::PointXYZI> cloud_out = *cluster;
// Allocate enough space and copy the basics
cloud_out.points.resize (indices.indices.size ());
cloud_out.header = cloud_in.header;
cloud_out.width = std::uint32_t (indices.indices.size ());
cloud_out.height = 1;
cloud_out.is_dense = cloud_in.is_dense;
cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_;
cloud_out.sensor_origin_ = cloud_in.sensor_origin_;
// Iterate over each point
for (std::size_t i = 0; i < indices.indices.size (); ++i) {
pcl::copyPoint (cloud_in.points[indices.indices[i]], cloud_out.points[i]);
}
cloud_clusters.push_back(cluster);
}
zhz03 commented
copyPointCloud
Can you talk more about how did you solve this issue? Thanks