• 博客园logo
  • 会员
  • 众包
  • 新闻
  • 博问
  • 闪存
  • 赞助商
  • HarmonyOS
  • Chat2DB
    • 搜索
      所有博客
    • 搜索
      当前博客
  • 写随笔 我的博客 短消息 简洁模式
    用户头像
    我的博客 我的园子 账号设置 会员中心 简洁模式 ... 退出登录
    注册 登录
MKT-porter
博客园    首页    新随笔    联系   管理    订阅  订阅
camke(4)配置sophus

0视觉SLAM十四讲slambook2示例代码

git clone --recursive https://github.com/gaoxiang12/slambook2.git

由于里面的3rdparty文件夹内所有内容都来自于其他github仓库,所以需要加上--recursive参数,不然克隆下来的内容不完整。
  如果你没有安装配置好git,也可以通过下载zip文件的形式直接下载代码。

自带版本

 

 

1eigen版本

卸载

sudo rm -rf /usr/include/eigen3 /usr/lib/cmake/eigen3 /usr/share/doc/libeigen3-dev /usr/share/pkgconfig/eigen3.pc /var/lib/dpkg/info/libeigen3-dev.list /var/lib/dpkg/info/libeigen3-dev.md5sums  

正确方法:
(1)在官网(http://eigen.tuxfamily.org/index.php?title=Main_Page)下载安装包:eigen-3.3.7.tar.bz2 ,然后提取到此处
(2)进入文件夹eigen-3.3.7,右键在终端打开。
(3)进行安装  

mkdir build

cd build

cmake ..

sudo make install

 

3安装fmt8.1.1

https://fmt.dev/8.1.1/index.html

mkdir build

cd build

cmake ..

sudo make install

  

4 编译

4-1 修改error

 

 在Sophus目录下,打开CMakeLists.txt文件,在里面加上如下一行代码(不加的话在make的时候会报错):

set(CMAKE_CXX_FLAGS "-Wno-error=deprecated-declarations -Wno-deprecated-declarations ")

  

4-2 开始编译

 

mkdir build

cd build

cmake ..

sudo make install

  

 

使用

CMakeLists.txt

cmake_minimum_required(VERSION 3.0)
project(useSophus)

# 为使用 sophus,需要使用find_package命令找到它
# find_package(fmt REQUIRED)# SE3库
# set(FMT_LIBRARIES fmt::fmt)
find_package(Sophus REQUIRED)
include_directories(${Sophus_INCLUDE_DIRS})

# Eigen
#include_directories(${EIGEN3_INCLUDE_DIRS})
include_directories("/usr/local/include/eigen3") #自己编译的库


add_executable(useSophus useSophus.cpp)
#target_link_libraries(useSophus Sophus::Sophus ${FMT_LIBRARIES})

  useSophus.cpp

#include <iostream>
#include <cmath>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include "sophus/se3.hpp"

using namespace std;
using namespace Eigen;

/// 本程序演示sophus的基本用法

int main(int argc, char **argv) {

  // 沿Z轴转90度的旋转矩阵
  Matrix3d R = AngleAxisd(M_PI / 2, Vector3d(0, 0, 1)).toRotationMatrix();
  // 或者四元数
  Quaterniond q(R);
  Sophus::SO3d SO3_R(R);              // Sophus::SO3d可以直接从旋转矩阵构造
  Sophus::SO3d SO3_q(q);              // 也可以通过四元数构造
  // 二者是等价的
  cout << "SO(3) from matrix:\n" << SO3_R.matrix() << endl;
  cout << "SO(3) from quaternion:\n" << SO3_q.matrix() << endl;
  cout << "they are equal" << endl;

  // 使用对数映射获得它的李代数
  Vector3d so3 = SO3_R.log();
  cout << "so3 = " << so3.transpose() << endl;
  // hat 为向量到反对称矩阵
  cout << "so3 hat=\n" << Sophus::SO3d::hat(so3) << endl;
  // 相对的,vee为反对称到向量
  cout << "so3 hat vee= " << Sophus::SO3d::vee(Sophus::SO3d::hat(so3)).transpose() << endl;

  // 增量扰动模型的更新
  Vector3d update_so3(1e-4, 0, 0); //假设更新量为这么多
  Sophus::SO3d SO3_updated = Sophus::SO3d::exp(update_so3) * SO3_R;
  cout << "SO3 updated = \n" << SO3_updated.matrix() << endl;

  cout << "*******************************" << endl;
  // 对SE(3)操作大同小异
  Vector3d t(1, 0, 0);           // 沿X轴平移1
  Sophus::SE3d SE3_Rt(R, t);           // 从R,t构造SE(3)
  Sophus::SE3d SE3_qt(q, t);            // 从q,t构造SE(3)
  cout << "SE3 from R,t= \n" << SE3_Rt.matrix() << endl;
  cout << "SE3 from q,t= \n" << SE3_qt.matrix() << endl;
  // 李代数se(3) 是一个六维向量,方便起见先typedef一下
  typedef Eigen::Matrix<double, 6, 1> Vector6d;
  Vector6d se3 = SE3_Rt.log();
  cout << "se3 = " << se3.transpose() << endl;
  // 观察输出,会发现在Sophus中,se(3)的平移在前,旋转在后.
  // 同样的,有hat和vee两个算符
  cout << "se3 hat = \n" << Sophus::SE3d::hat(se3) << endl;
  cout << "se3 hat vee = " << Sophus::SE3d::vee(Sophus::SE3d::hat(se3)).transpose() << endl;

  // 最后,演示一下更新
  Vector6d update_se3; //更新量
  update_se3.setZero();
  update_se3(0, 0) = 1e-4;
  Sophus::SE3d SE3_updated = Sophus::SE3d::exp(update_se3) * SE3_Rt;
  cout << "SE3 updated = " << endl << SE3_updated.matrix() << endl;

  return 0;
}

  

 

posted on 2021-05-31 16:22  MKT-porter  阅读(242)  评论(0)    收藏  举报
刷新页面返回顶部
博客园  ©  2004-2025
浙公网安备 33010602011771号 浙ICP备2021040463号-3