2 Commits

Author SHA1 Message Date
NuoDaJia02
41d9d822bc use RPATH 2025-12-09 09:48:47 +08:00
NuoDaJia02
f045bfcc34 switch pcl from 1.10->1.12 2025-12-08 14:26:04 +08:00
18 changed files with 47 additions and 49 deletions

View File

@@ -26,15 +26,9 @@ find_package(OpenMP)
find_package(Eigen3)
set(CMAKE_PREFIX_PATH "/home/demo/deps_install" ${CMAKE_PREFIX_PATH})
set(CMAKE_INCLUDE_PATH "/home/demo/deps_install/include" ${CMAKE_INCLUDE_PATH})
set(CMAKE_LIBRARY_PATH "/home/demo/deps_install/lib" ${CMAKE_LIBRARY_PATH})
set(PCL_DIR /home/demo/deps_install/share/pcl-1.10)
set(PCL_ROOT /home/demo/deps_install)
find_package(PCL REQUIRED)
find_package(PCL 1.12 REQUIRED)
message("##################" ${PCL_INCLUDE_DIRS})
message("##################" ${PCL_LIBRARIES})
@@ -46,6 +40,13 @@ if (OPENMP_FOUND)
set (CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
endif()
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--disable-new-dtags")
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -Wl,--disable-new-dtags")
set(CMAKE_SKIP_BUILD_RPATH FALSE)
set(CMAKE_BUILD_WITH_INSTALL_RPATH TRUE)
set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib")
set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE)
include_directories(
include/${PROJECT_NAME}
${pcl_conversions_INCLUDE_DIRS}
@@ -53,17 +54,13 @@ include_directories(
${PCL_INCLUDE_DIRS}
${YAML_CPP_INCLUDE_DIR}
/user/include
/home/demo/deps_install/include/pcl-1.10
)
link_directories(
/home/demo/deps_install/lib
)
add_subdirectory(src)
#add_subdirectory(apps/nodelets)
add_subdirectory(apps/nodelets)
install(
DIRECTORY launch

View File

@@ -49,14 +49,14 @@ double orientation_variance_;
bool reverse_tf_;
tf2::Quaternion hamiltonToTFQuaternion(double q0, double q1, double q2,
double q3);
boost::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
int main(int argc, char **argv)
{
// ROS parameter stuff;
rclcpp::init(argc, argv);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("imu_preprocessing_node");
tf_broadcaster_ = boost::shared_ptr<tf2_ros::TransformBroadcaster>(new tf2_ros::TransformBroadcaster(node));
tf_broadcaster_ = std::shared_ptr<tf2_ros::TransformBroadcaster>(new tf2_ros::TransformBroadcaster(node));
string path_to_param_file;
node->declare_parameter("file_params", "/home/solomon/ws_humble_pcl_10/src/lio_locus_humble/config/parameters_lio_locus.yaml");

View File

@@ -3,7 +3,6 @@
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <vector>
typedef pcl::PointXYZINormal PointF;
@@ -13,11 +12,11 @@ typedef pcl::PointCloud<PointF>::Ptr pclPtr;
typedef std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>>
MatricesVector;
typedef boost::shared_ptr<MatricesVector> MatricesVectorPtr;
typedef std::shared_ptr<MatricesVector> MatricesVectorPtr;
typedef std::vector<Eigen::Matrix3f, Eigen::aligned_allocator<Eigen::Matrix3f>>
MatricesVectorf;
typedef boost::shared_ptr<MatricesVectorf> MatricesVectorfPtr;
typedef std::shared_ptr<MatricesVectorf> MatricesVectorfPtr;
template <typename T>
using MatricesVectorT =
@@ -25,4 +24,4 @@ using MatricesVectorT =
Eigen::aligned_allocator<Eigen::Matrix<T, 3, 3>>>;
template <typename T>
using MatricesVectorTPtr = boost::shared_ptr<MatricesVectorT<T>>;
using MatricesVectorTPtr = std::shared_ptr<MatricesVectorT<T>>;

View File

@@ -10,8 +10,8 @@ namespace geometry_utils
template <typename T, size_t N, size_t M>
struct MatrixNxMBase
{
typedef typename boost::shared_ptr<MatrixNxMBase<T, N, M>> Ptr;
typedef typename boost::shared_ptr<const MatrixNxMBase<T, N, M>> ConstPtr;
typedef typename std::shared_ptr<MatrixNxMBase<T, N, M>> Ptr;
typedef typename std::shared_ptr<const MatrixNxMBase<T, N, M>> ConstPtr;
static const size_t size = N * M;
static const size_t nrows = N;

View File

@@ -9,8 +9,8 @@ namespace geometry_utils
template <typename T>
struct Transform2Base
{
typedef boost::shared_ptr<Transform2Base> Ptr;
typedef boost::shared_ptr<const Transform2Base> ConstPtr;
typedef std::shared_ptr<Transform2Base> Ptr;
typedef std::shared_ptr<const Transform2Base> ConstPtr;
Vector2Base<T> translation;
Rotation2Base<T> rotation;

View File

@@ -10,8 +10,8 @@ namespace geometry_utils
template <typename T>
struct Transform3Base
{
typedef boost::shared_ptr<Transform3Base> Ptr;
typedef boost::shared_ptr<const Transform3Base> ConstPtr;
typedef std::shared_ptr<Transform3Base> Ptr;
typedef std::shared_ptr<const Transform3Base> ConstPtr;
Vector3Base<T> translation;
Rotation3Base<T> rotation;

View File

@@ -13,8 +13,8 @@ namespace geometry_utils
template <typename T, size_t N>
struct VectorNBase
{
typedef typename boost::shared_ptr<VectorNBase<T, N>> Ptr;
typedef typename boost::shared_ptr<const VectorNBase<T, N>> ConstPtr;
typedef typename std::shared_ptr<VectorNBase<T, N>> Ptr;
typedef typename std::shared_ptr<const VectorNBase<T, N>> ConstPtr;
static const size_t length = N;

View File

@@ -65,7 +65,7 @@ class CloudPreProcessor {
public:
CloudPreProcessor();
virtual ~CloudPreProcessor();
typedef boost::shared_ptr<CloudPreProcessor> Ptr;
typedef std::shared_ptr<CloudPreProcessor> Ptr;
// convert ROS cloud message to PCL cloud format;
static pcl::PointCloud<pcl::PointXYZINormal>::Ptr adaptCloudForm(

View File

@@ -38,11 +38,11 @@ using point_cloud_odometry::PointCloudOdometry;
using point_cloud_localization::PointCloudLocalization;
typedef pcl::PointCloud<pcl::PointXYZINormal> PointCloudType;
typedef boost::shared_ptr<PointCloudOdometry> PointCloudOdometryPtr;
typedef boost::shared_ptr<PointCloudLocalization> PointCloudLocalizationPtr;
typedef boost::shared_ptr<PointCloudIkdTreeMapper> PointCloudIkdTreeMapperPtr;
// typedef boost::shared_ptr<PointCloudMultiThreadedMapper> PointCloudMultiThreadedMapperPtr;
// typedef boost::shared_ptr<PointCloudMapper> PointCloudMapperPtr;
typedef std::shared_ptr<PointCloudOdometry> PointCloudOdometryPtr;
typedef std::shared_ptr<PointCloudLocalization> PointCloudLocalizationPtr;
typedef std::shared_ptr<PointCloudIkdTreeMapper> PointCloudIkdTreeMapperPtr;
// typedef std::shared_ptr<PointCloudMultiThreadedMapper> PointCloudMultiThreadedMapperPtr;
// typedef std::shared_ptr<PointCloudMapper> PointCloudMapperPtr;
#include <Eigen/Geometry>
#include <Eigen/Core>
@@ -85,7 +85,7 @@ class LioLocus {
public:
LioLocus();
virtual ~LioLocus();
typedef boost::shared_ptr<LioLocus> Ptr;
typedef std::shared_ptr<LioLocus> Ptr;
//------------------------------------------------------------------
// initialization;

View File

@@ -95,14 +95,14 @@ public:
typedef PointIndices::ConstPtr PointIndicesConstPtr;
typedef std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>> MatricesVector;
typedef boost::shared_ptr<MatricesVector> MatricesVectorPtr;
typedef boost::shared_ptr<const MatricesVector> MatricesVectorConstPtr;
typedef std::shared_ptr<MatricesVector> MatricesVectorPtr;
typedef std::shared_ptr<const MatricesVector> MatricesVectorConstPtr;
typedef typename Registration<PointSource, PointTarget>::KdTree InputKdTree;
typedef typename Registration<PointSource, PointTarget>::KdTreePtr InputKdTreePtr;
typedef boost::shared_ptr<MultithreadedGeneralizedIterativeClosestPoint<PointSource, PointTarget>> Ptr;
typedef boost::shared_ptr<const MultithreadedGeneralizedIterativeClosestPoint<PointSource, PointTarget>> ConstPtr;
typedef std::shared_ptr<MultithreadedGeneralizedIterativeClosestPoint<PointSource, PointTarget>> Ptr;
typedef std::shared_ptr<const MultithreadedGeneralizedIterativeClosestPoint<PointSource, PointTarget>> ConstPtr;
typedef Eigen::Matrix<double, 6, 1> Vector6d;

View File

@@ -89,10 +89,10 @@ protected:
typedef typename TargetGrid::LeafConstPtr TargetGridLeafConstPtr;
public:
typedef boost::shared_ptr<
typedef std::shared_ptr<
NormalDistributionsTransform<PointSource, PointTarget>>
Ptr;
typedef boost::shared_ptr<
typedef std::shared_ptr<
const NormalDistributionsTransform<PointSource, PointTarget>>
ConstPtr;

View File

@@ -81,8 +81,8 @@ protected:
typedef typename PointCloud::ConstPtr PointCloudConstPtr;
public:
typedef boost::shared_ptr<pcl::VoxelGrid<PointT>> Ptr;
typedef boost::shared_ptr<const pcl::VoxelGrid<PointT>> ConstPtr;
typedef std::shared_ptr<pcl::VoxelGrid<PointT>> Ptr;
typedef std::shared_ptr<const pcl::VoxelGrid<PointT>> ConstPtr;
/** \brief Simple structure to hold a centroid, covarince and the number of
* points in a leaf. Inverse covariance, eigen vectors and engen values are

View File

@@ -1,5 +1,5 @@
add_subdirectory(point_cloud_odometry)
add_subdirectory(point_cloud_localization)
add_subdirectory(point_cloud_mapper)
#add_subdirectory(lio_locus)
add_subdirectory(lio_locus)

View File

@@ -214,7 +214,7 @@ bool PointCloudLocalization::SetupICP()
LOG(INFO) <<
"RegistrationMethod::GICP activated.";
pcl::MultithreadedGeneralizedIterativeClosestPoint<PointF, PointF>::Ptr gicp =
boost::make_shared<
std::make_shared<
pcl::MultithreadedGeneralizedIterativeClosestPoint<
PointF, PointF>>();
@@ -253,7 +253,7 @@ bool PointCloudLocalization::SetupICP()
{
LOG(INFO) << "RegistrationMethod::NDT activated.";
pclomp::NormalDistributionsTransform<PointF, PointF>::Ptr ndt_omp =
boost::make_shared<
std::make_shared<
pclomp::NormalDistributionsTransform<PointF, PointF>>();
ndt_omp->setTransformationEpsilon(params_.tf_epsilon);

View File

@@ -1,4 +1,6 @@
#include <point_cloud_localization/utils.h>
#include <Eigen/Core>
#include <Eigen/Eigenvalues>
void addNormal(const PointCloudF &cloud,
pcl::PointCloud<pcl::PointNormal>::Ptr &cloud_with_normals,

View File

@@ -6,12 +6,11 @@ add_library(point_cloud_mapper SHARED
target_include_directories(point_cloud_mapper PUBLIC
# ${PCL_INCLUDE_DIRS}
/home/demo/deps_install/include/pcl-1.10
${PCL_INCLUDE_DIRS}
)
target_link_libraries(point_cloud_mapper
${PCL_LIBRARIRES}
${PCL_LIBRARIES}
${YAML_CPP_LIBRARIES}
glog
OpenMP::OpenMP_CXX

View File

@@ -1,4 +1,5 @@
#include <omp.h>
#include <pcl/types.h>
#include <pcl/octree/octree_iterator.h>
#include <pcl/search/impl/search.hpp>
#include <point_cloud_mapper/PointCloudIkdTreeMapper.h>

View File

@@ -129,7 +129,7 @@ bool PointCloudOdometry::SetupICP() {
case RegistrationMethod::GICP: {
LOG(INFO) << "RegistrationMethod::GICP activated.";
pcl::MultithreadedGeneralizedIterativeClosestPoint<PointF, PointF>::Ptr gicp =
boost::make_shared<
std::make_shared<
pcl::MultithreadedGeneralizedIterativeClosestPoint<
PointF, PointF> >();
@@ -168,7 +168,7 @@ bool PointCloudOdometry::SetupICP() {
case RegistrationMethod::NDT: {
LOG(INFO) << "RegistrationMethod::NDT activated.";
pclomp::NormalDistributionsTransform<PointF, PointF>::Ptr ndt_omp =
boost::make_shared<
std::make_shared<
pclomp::NormalDistributionsTransform<PointF, PointF>>();
ndt_omp->setTransformationEpsilon(params_.icp_tf_epsilon);