XTDrone和PX4学习期间问题记录(一)

Written By PiscesAlpaca

前言:

出现问题可以去官方网站http://ceres-solver.org/index...查看文档,搜索引擎很难搜到对应的问题。(不过我写了这些问题的解决办法,没准以后就能搜到了hh

1.视觉SLAM篇

URL:视觉SLAM · 语雀

ORBSLAM2编译

编译依赖见ORBSLAM2编译依赖

注意该ORBSLAM2是在原版本基础上略做修改,其虽然支持ROS,但不是标准的ROS架构,因此不能采用catkin build编译。

cp -r ~/XTDrone/sensing/slam/vslam/ORB_SLAM2/ ~/catkin_ws/src/
mkdir ~/catkin_ws/scripts/
cp ~/catkin_ws/src/ORB_SLAM2/xtdrone* ~/catkin_ws/scripts/
cd ~/catkin_ws/src/ORB_SLAM2
chmod +x build.sh
./build.sh
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/catkin_ws/src/ORB_SLAM2/Examples/ROS #将这句放到~/.bashrc中,以后使用更方便
chmod +x build_ros.sh
./build_ros.sh

问题:在进行./build.sh时,遇到了make[2]: *** No rule to make target '../Thirdparty/DBoW2/lib/libDBoW2.so', needed by '../lib/libORB_SLAM3.so'. Stop.

解决办法:手动cd进目录ORB_SLAM3/Thirdparty/DBoW2/build,依次运行cmake ..build -j4,之后就可以发现libDBoW2.so文件生成在lib目录下,再按照教程运行./build.sh即可100%完成编译。

2.三维激光SLAM篇

问题:在进行catkin_make命令时,遇到了`/home/pisces/catkin_ws/src/A- LOAM/src/laserOdometry.cpp:286:29: error: expected type-specifier
286 | new ceres::EigenQuaternionParameterization();

  |                             ^~~~~                                   `

解决办法:

官方文档显示

EigenQuaternionParameterization is deprecated. It will be
removed in version 2.2.0 of Ceres Solver. Please use EigenQuaternionManifold instead.

证明EigenQuaternionParameterization已经过时,需要使用EigenQuaternionManifold替换,即:

ceres::LocalParameterization *q_parameterization = new ceres::EigenQuaternionParameterization();

替换为:``

ceres::LocalParameterization *q_parameterization = new ceres::EigenQuaternionManifold();

3.视觉惯性里程计

问题:

`/home/pisces/catkin_ws/src/VINS-Fusion/camera_models/src/calib/CameraCalibration.cc:508:17: error: cannot convert ‘camodocal::EigenQuaternionParameterization’ to ‘ceres::LocalParameterization’ in initialization

         new EigenQuaternionParameterization;
             ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~`

解决方法:更改ceres::LocalParameterization*为ceres::Manifold*

        ceres::Manifold* quaternionParameterization =
            new EigenQuaternionParameterization;

问题:

`/home/pisces/catkin_ws/src/VINS-Fusion/camera_models/src/calib/CameraCalibration.cc:510:17: error: ‘class ceres::Problem’ has no member named ‘SetParameterization’; did you mean ‘SetParameterLowerBound’?

     problem.SetParameterization(transformVec.at(i).rotationData(),
             ^~~~~~~~~~~~~~~~~~~
             SetParameterLowerBound`

解决方法:

This method is deprecated and will be removed in Ceres Solver version 2.2.0. Please move to using the SetManifold instead.

        problem.SetManifold(transformVec.at(i).rotationData(),
                                    quaternionParameterization);

问题:

`/home/pisces/catkin_ws/src/VINS-Fusion/global_fusion/src/globalOpt.cpp:109:72: error: expected type-specifier

         ceres::LocalParameterization* local_parameterization = new ceres::QuaternionParameterization();
                                                                    ^~~~~`

解决方法:

QuaternionParameterization is deprecated. It will be removed in version 2.2.0 of Ceres Solver. Please use QuaternionManifold instead.

            ceres::Manifold* local_parameterization = new ceres::QuaternionManifold();

问题:

`/home/pisces/catkin_ws/src/VINS-Fusion/camera_models/src/calib/CameraCalibration.cc:508:17: error: invalid new-expression of abstract class type ‘camodocal::EigenQuaternionParameterization’

         new EigenQuaternionParameterization;
             ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~`

解决方法:本质是因为新继承的Manifold类出现了新的纯虚函数,只需要在EigenQuaternionParameterization类实现就行

在EigenQuaternionParameterization类public:下加入

    virtual int AmbientSize() const {return 7;}
    virtual int TangentSize() const {return 1;}
    virtual bool PlusJacobian(const double* x, double* jacobian) const {return 1;}
    virtual bool Minus(const double* y,
                       const double* x,
                       double* y_minus_x) const {return 1;}
    virtual bool MinusJacobian(const double* x, double* jacobian) const {return 1;}

class EigenQuaternionParameterization : public ceres::Manifold
{
public:
    virtual ~EigenQuaternionParameterization() {}
    virtual bool Plus(const double* x,
                      const double* delta,
                      double* x_plus_delta) const;
    virtual bool ComputeJacobian(const double* x,
                                 double* jacobian) const;
    virtual int GlobalSize() const { return 4; }
    virtual int LocalSize() const { return 3; }

    //edit by PiscesAlpaca
    virtual int AmbientSize() const {return 1;}
    virtual int TangentSize() const {return 1;}
    virtual bool PlusJacobian(const double* x, double* jacobian) const {return 1;}
    virtual bool Minus(const double* y,
                       const double* x,
                       double* y_minus_x) const {return 1;}
    virtual bool MinusJacobian(const double* x, double* jacobian) const {return 1;}

private:
    template<typename T>
    void EigenQuaternionProduct(const T z[4], const T w[4], T zw[4]) const;
};

问题:

`/home/pisces/catkin_ws/src/VINS-Fusion/loop_fusion/src/pose_graph.h:134:24: error: ‘AutoDiffLocalParameterization’ in namespace ‘ceres’ does not name a template type

 return (new ceres::AutoDiffLocalParameterization<AngleLocalParameterization,
                    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~`

解决方法:

AutoDiffParameterization is deprecated. It will be removed in version 2.2.0 of Ceres Solver. Please use AutoDiffManifold instead.

  static ceres::Manifold* Create() {
    return (new ceres::AutoDiffManifold <AngleLocalParameterization,
                                                     1, 1>);
  }

注意:如果进行更改后编译提示缺少Plus和Minus函数,可以在pose_graph.h文件加入

class AngleLocalParameterization {
 public:

  template <typename T>
  bool operator()(const T* theta_radians, const T* delta_theta_radians,
                  T* theta_radians_plus_delta) const {
    *theta_radians_plus_delta =
        NormalizeAngle(*theta_radians + *delta_theta_radians);

    return true;
  }

  //edit by pisces
    bool Plus(const double* x,
              const double* delta,
              double* x_plus_delta) {
        return true;
    }
    //edit by pisces
    bool Minus(const double* y,
               const double* x,
               double* y_minus_x) {
        return true;
    }
    //edit by pisces
    template <typename T>
    bool Plus(const T* x,
              const T* delta,
              T* x_plus_delta) const{
        return true;
    }
    //edit by pisces
    template <typename T>
    bool Minus(const T* y,
               const T* x,
               T* y_minus_x) const{
        return true;
    }

    static ceres::Manifold* Create() {
    return (new ceres::AutoDiffManifold <AngleLocalParameterization,
                                                     1, 1>);
  }
};

//edit by pisces为增加的函数

问题:

`/home/pisces/catkin_ws/src/VINS-Fusion/vins_estimator/src/estimator/../factor/pose_local_parameterization.h:16:49: error: invalid use of incomplete type ‘class ceres::LocalParameterization’
class PoseLocalParameterization : public ceres::LocalParameterization

                                             ^~~~~~~~~~~~~~~~~~~~~`

解决方法:更改ceres::LocalParameterization*为ceres::Manifold*

同本节问题1

问题:

`/home/pisces/catkin_ws/src/VINS-Fusion/loop_fusion/src/pose_graph.cpp:474:52: error: cannot convert ‘ceres::Manifold’ to ‘ceres::LocalParameterization’ in initialization

             AngleLocalParameterization::Create();
                                                ^`

解决方法:

            ceres::Manifold* angle_local_parameterization =
                AngleLocalParameterization::Create();

不过上述方法最终没有能够让VINS-Fusion接收到正确数据,还是对ceres进行了降级才实现,版本为1.14。如果有使用上述方法成功的读者可以在评论告诉我~

欢迎指出错误和不足~

转载请注明出处!

本篇发布在以下博客或网站:

双鱼座羊驼 - 知乎 (zhihu.com)

双鱼座羊驼的博客_CSDN博客

双鱼座羊驼 - SegmentFault 思否

双鱼座羊驼 的个人主页 - 动态 - 掘金 (juejin.cn)

双鱼座羊驼 - 博客园 (cnblogs.com)


双鱼座羊驼
1 声望0 粉丝