sophus庫使用

非模板類的sophus庫

#include <iostream>
#include <cmath>
using namespace std; 

#include <Eigen/Core>
#include <Eigen/Geometry>

#include "sophus/so3.h"
#include "sophus/se3.h"

int main( int argc, char** argv )
{
    // 沿Z軸轉90度的旋轉矩陣
    Eigen::Matrix3d R = Eigen::AngleAxisd(M_PI/2,       Eigen::Vector3d(0,0,1)).toRotationMatrix();
    
    Sophus::SO3 SO3_R(R);               // Sophus::SO(3)可以直接從旋轉矩陣構造
    Sophus::SO3 SO3_v( 0, 0, M_PI/2 );  // 亦可從旋轉向量構造
    Eigen::Quaterniond q(R);            // 或者四元數
    Sophus::SO3 SO3_q( q );
    // 上述表達方式都是等價的
    // 輸出SO(3)時,以so(3)形式輸出
    cout<<"SO(3) from matrix: "<<SO3_R<<endl;
    cout<<"SO(3) from vector: "<<SO3_v<<endl;
    cout<<"SO(3) from quaternion :"<<SO3_q<<endl;
    
    // 使用對數映射獲得它的李代數
    Eigen::Vector3d so3 = SO3_R.log();
    cout<<"so3 = "<<so3.transpose()<<endl;
    // hat 爲向量到反對稱矩陣
    cout<<"so3 hat=\n"<<Sophus::SO3::hat(so3)<<endl;
    // 相對的,vee爲反對稱到向量
    cout<<"so3 hat vee= "<<Sophus::SO3::vee( Sophus::SO3::hat(so3) ).transpose()<<endl; // transpose純粹是爲了輸出美觀一些
    
    // 增量擾動模型的更新
    Eigen::Vector3d update_so3(1e-4, 0, 0); //假設更新量爲這麼多
    Sophus::SO3 SO3_updated = Sophus::SO3::exp(update_so3)*SO3_R;
    cout<<"SO3 updated = "<<SO3_updated<<endl;
    
    /********************萌萌的分割線*****************************/
    cout<<"************我是分割線*************"<<endl;
    // 對SE(3)操作大同小異
    Eigen::Vector3d t(1,0,0);           // 沿X軸平移1
    Sophus::SE3 SE3_Rt(R, t);           // 從R,t構造SE(3)
    Sophus::SE3 SE3_qt(q,t);            // 從q,t構造SE(3)
    cout<<"SE3 from R,t= "<<endl<<SE3_Rt<<endl;
    cout<<"SE3 from q,t= "<<endl<<SE3_qt<<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 = "<<endl<<Sophus::SE3::hat(se3)<<endl;
    cout<<"se3 hat vee = "<<Sophus::SE3::vee( Sophus::SE3::hat(se3) ).transpose()<<endl;
    
    // 最後,演示一下更新
    Vector6d update_se3; //更新量
    update_se3.setZero();
    update_se3(0,0) = 1e-4d;
    Sophus::SE3 SE3_updated = Sophus::SE3::exp(update_se3)*SE3_Rt;
    cout<<"SE3 updated = "<<endl<<SE3_updated.matrix()<<endl;
    
    return 0;
}

Sophus的cmake文件

cmake_minimum_required( VERSION 2.8 )
project( useSophus )

# 爲使用 sophus,您需要使用find_package命令找到它
find_package( Sophus REQUIRED )
include_directories( ${Sophus_INCLUDE_DIRS} )

add_executable( useSophus useSophus.cpp )
target_link_libraries( useSophus ${Sophus_LIBRARIES} )

新版(模板類)sophus

代碼示例:

#include <iostream>
#include <cmath>
using namespace std; 
 
#include <Eigen/Core>
#include <Eigen/Geometry>
 
#include "sophus/so3.hpp"
#include "sophus/se3.hpp"
 
int main( int argc, char** argv )
{
    // 沿Z軸轉90度的旋轉矩陣
    Eigen::Matrix3d R = Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d(0,0,1)).toRotationMatrix();
    
    Sophus::SO3<double> SO3_R(R);               // Sophus::SO(3)可以直接從旋轉矩陣構造
//  Sophus::SO3 SO3_v( 0, 0, M_PI/2 );  // 亦可從旋轉向量構造 
    Eigen::Quaterniond q(R);            // 或者四元數
    Sophus::SO3<double> SO3_q( q );
    // 上述表達方式都是等價的
    // 輸出SO(3)時,以so(3)形式輸出
    cout<<"SO(3) from matrix: "<<SO3_R.log()<<endl;
//  cout<<"SO(3) from vector: "<<SO3_v<<endl;
    cout<<"SO(3) from quaternion :"<<SO3_q.log()<<endl;
    
    // 使用對數映射獲得它的李代數
    Eigen::Vector3d so3 = SO3_R.log();
    cout<<"so3 = "<<so3.transpose()<<endl;
    // hat 爲向量到反對稱矩陣
    cout<<"so3 hat=\n"<<Sophus::SO3<double>::hat(so3)<<endl;
    // 相對的,vee爲反對稱到向量
    cout<<"so3 hat vee= "<<Sophus::SO3<double>::vee( Sophus::SO3<double>::hat(so3) ).transpose()<<endl; // transpose純粹是爲了輸出美觀一些
    
    // 增量擾動模型的更新
    Eigen::Vector3d update_so3(1e-4, 0, 0); //假設更新量爲這麼多
    Sophus::SO3<double> SO3_updated = Sophus::SO3<double>::exp(update_so3)*SO3_R;
    cout<<"SO3 updated = "<<SO3_updated.log()<<endl;
    
    //--------------------------------------------//
    // 對SE(3)操作大同小異
    Eigen::Vector3d t(1,0,0);           // 沿X軸平移1
    Sophus::SE3<double> SE3_Rt(R, t);           // 從R,t構造SE(3)
    Sophus::SE3<double> SE3_qt(q,t);            // 從q,t構造SE(3)
    cout<<"SE3 from R,t= "<<endl<<SE3_Rt.log()<<endl;
    cout<<"SE3 from q,t= "<<endl<<SE3_qt.log()<<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 = "<<endl<<Sophus::SE3<double>::hat(se3)<<endl;
    cout<<"se3 hat vee = "<<Sophus::SE3<double>::vee( Sophus::SE3<double>::hat(se3) ).transpose()<<endl;
    
    // 最後,演示一下更新
    Vector6d update_se3; //更新量
    update_se3.setZero();
    update_se3(0,0) = 1e-4d;
    Sophus::SE3<double> SE3_updated = Sophus::SE3<double>::exp(update_se3)*SE3_Rt;
    cout<<"SE3 updated = "<<endl<<SE3_updated.matrix()<<endl;
    
    return 0;
}
發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章