Skip to content

Commit

Permalink
Fix the crash issue by unmatched compile options, see README.
Browse files Browse the repository at this point in the history
  • Loading branch information
wz committed Dec 6, 2022
1 parent 3052508 commit 82063e0
Show file tree
Hide file tree
Showing 8 changed files with 26 additions and 4 deletions.
7 changes: 6 additions & 1 deletion README.MD
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,12 @@
### Prerequisites
- Install depends follow the instructions of ["cartographer"](https://google-cartographer.readthedocs.io/en/latest/index.html) and ["cartographer_ros"](https://google-cartographer-ros.readthedocs.io/en/latest/compilation.html) respectively.
- Build [OpenCV 3.3.1](https://opencv.org/releases/page/2/) (other version may work fine if it includes implementation of SURF keypoint detector) from source with "opencv_contrib"
- [GTSAM 4.0.2](https://github.com/borglab/gtsam/tree/4.0.2)
- Build [GTSAM 4.0.2](https://github.com/borglab/gtsam/tree/4.0.2) with compile options as follows:

```cmake -DGTSAM_USE_SYSTEM_EIGEN=ON -DGTSAM_WITH_TBB=OFF -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF -DGTSAM_COMPILE_OPTIONS_PUBLIC="" ..```
- Build [PCL 1.8.0]() with compile options as follows:

```cmake -DPCL_ENABLE_SSE=OFF ..```
---
### Build
- Clone this repository in your ROS workspace
Expand Down
6 changes: 3 additions & 3 deletions src/cartographer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,11 @@ find_package(LuaGoogle REQUIRED)
find_package(Protobuf 3.0.0 REQUIRED)

# add for lins, wz
find_package(PCL REQUIRED QUIET)
find_package(PCL 1.8.0 REQUIRED)
find_package(VTK REQUIRED)
find_package(GTSAM REQUIRED QUIET)
find_package(GTSAM 4.0.2 REQUIRED)
# self built, with SURF
set(OpenCV_DIR "/home/wz/github/opencv-3.3.1/install/share/OpenCV")
set(OpenCV_DIR "/home/wz/study_hub/opencv-3.3.1/install/share/OpenCV")
find_package(OpenCV 3.3.1 REQUIRED)
# find_package(catkin REQUIRED COMPONENTS ndt_omp)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@ class GravityEstimator {
const std::deque<Vector3d> &Vs,
const double gnorm,
Vector3d &g_approx);
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ struct IMUNoise{
};
class IntegrationBase {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
IntegrationBase() = delete;
IntegrationBase(
const Eigen::Vector3d &_linearized_ba,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ using Eigen::VectorXd;
// template <typename T>
class Rigid3dWithPreintegrator{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
explicit Rigid3dWithPreintegrator(){
transform = transform::Rigid3d::Identity();
pre_integration = nullptr;
Expand All @@ -32,6 +33,7 @@ class Rigid3dWithPreintegrator{
// more accurate in initialization via experiments.
class Rigid3dWithVINSPreintegrator{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
explicit Rigid3dWithVINSPreintegrator(){
transform = transform::Rigid3d::Identity();
pre_integration = nullptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1087,6 +1087,12 @@ bool LocalTrajectoryBuilder3D::AlignWithWorld() {

void LocalTrajectoryBuilder3D::InitCircularBuffers(){
Eigen::Vector3d zero_vec(0., 0., 0.);
all_laser_transforms_.clear();
Ps_.clear();
Rs_.clear();
Vs_.clear();
Bas_.clear();
Bgs_.clear();
for(size_t i = 0; i < frames_for_dynamic_initialization_+1; ++i){
all_laser_transforms_.push_back(Rigid3dWithVINSPreintegrator());
Ps_.push_back(zero_vec);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -276,6 +276,8 @@ class LocalTrajectoryBuilder3D {
std::deque<Rigid3dWithPreintegrator> g_est_transforms_;
std::deque<Rigid3dWithPreintegrator> g_est_transforms_tmp_;
std::deque<Eigen::Vector3d> g_est_Vs_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

} // namespace mapping
Expand Down
4 changes: 4 additions & 0 deletions src/cartographer/cartographer/transform/rigid_transform.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,8 @@ class Rigid2 {
private:
Vector translation_;
Rotation2D rotation_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

template <typename FloatType>
Expand Down Expand Up @@ -197,6 +199,8 @@ class Rigid3 {
private:
Vector translation_;
Quaternion rotation_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

template <typename FloatType>
Expand Down

0 comments on commit 82063e0

Please sign in to comment.